Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • gsaurel/talos-data
  • stack-of-tasks/talos-data
2 results
Show changes
Showing
with 110 additions and 859 deletions
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="robot" default="full_v2"/>
<arg name="gzpose" default="-x 0 -y 0 -z 1.0 -R 0.0 -P 0.0 -Y 0.0"/>
<!-- PAL Hardware gazebo config -->
<include file="$(find talos_controller_configuration)/launch/selective_rosparam_loader.launch">
<arg name="robot" value="$(arg robot)" />
<arg name="prefix" value="$(find talos_hardware_gazebo)/config/sensors/" />
</include>
<!-- PID gains -->
<rosparam command="load" file="$(find talos_data)/config/pids_stiff.yaml"/>
<!-- Spawn robot in Gazebo -->
<node pkg="gazebo_ros" type="spawn_model" name="spawn_model"
args="-urdf -param robot_description $(arg gzpose) -model talos" />
<node ns="/rgbd/rgb/high_res" pkg="image_proc" type="image_proc" name="image_proc_high_res"/>
<node ns="/rgbd/rgb" pkg="image_proc" type="image_proc" name="image_proc"/>
</launch>
File added
File added
Source diff could not be displayed: it is too large. Options to address this: view the blob.
<?xml version="1.0"?>
<package format="2">
<name>talos_data</name>
<version>1.0.4</version>
<version>2.1.0</version>
<description>The talos_data package</description>
<maintainer email="olivier.stasse@laas.fr">Olivier Stasse</maintainer>
<maintainer email="guilhem.saurel@laas.fr">Guilhem Saurel</maintainer>
<license>LGPL-3.0</license>
......
......@@ -30,8 +30,8 @@
<xacro:property name="var_enable_leg_passive" value="$(arg enable_leg_passive)"/>
<xacro:if value="${var_enable_leg_passive != 'true'}">
<xacro:include filename="$(find talos_data)/urdf/leg/leg.urdf.xacro" />
</xacro:if>
</xacro:if>
<xacro:include filename="$(find talos_data)/urdf/leg/foot_collision_$(arg foot_collision).urdf.xacro" />
<xacro:include filename="$(find talos_description_inertial)/urdf/inertial.xacro" />
......
......@@ -836,4 +836,3 @@
<color rgba="1.0 0.5 0.0 1.0"/>
</material>
</robot>
......@@ -2190,8 +2190,8 @@
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
</collision>
-->
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
......@@ -2516,8 +2516,8 @@
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
</collision>
-->
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
......@@ -2783,4 +2783,3 @@
<color rgba="1.0 0.5 0.0 1.0"/>
</material>
</robot>
......@@ -10,6 +10,7 @@
<!-- TODO AS: zeros should not be the default (self-colliding), but it is currently required for tests -->
<arg name="default_configuration_type" default="zeros"/>
<arg name="enable_leg_passive" default="true"/>
<arg name="enable_fixed_robot" default="true"/>
<!-- Robot description -->
<param
......@@ -18,7 +19,8 @@
'$(find talos_data)/robots/talos_$(arg robot).urdf.xacro'
foot_collision:=$(arg foot_collision)
enable_crane:=$(arg enable_crane)
enable_leg_passive:=$(arg enable_leg_passive)"
enable_leg_passive:=$(arg enable_leg_passive)
enable_fixed_robot:=$(arg enable_fixed_robot)"
/>
<rosparam command="load" file="$(find talos_data)/config/default_configuration_$(arg default_configuration_type).yaml" />
......
/*
* Copyright 2011 Nate Koenig & Andrew Howard
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#include "gazebo/physics/physics.hh"
#include "SpringPlugin.hh"
#include <ros/ros.h>
using namespace gazebo;
GZ_REGISTER_MODEL_PLUGIN(SpringPlugin)
/////////////////////////////////////////////////
SpringPlugin::SpringPlugin()
{
}
/////////////////////////////////////////////////
void SpringPlugin::Load(physics::ModelPtr lmodel,
sdf::ElementPtr lsdf)
{
this->model = lmodel;
// hardcoded params for this test
if (!lsdf->HasElement("joint_spring"))
ROS_ERROR_NAMED("SpringPlugin","No field joint_spring for SpringPlugin");
else
this->jointExplicitName = lsdf->Get<std::string>("joint_spring");
this->kpExplicit = lsdf->Get<double>("kp");
this->kdExplicit = lsdf->Get<double>("kd");
ROS_INFO_NAMED("SpringPlugin",
"Loading joint : %s kp: %f kd: %f",
this->jointExplicitName.c_str(),
this->kpExplicit,
this->kdExplicit);
}
/////////////////////////////////////////////////
void SpringPlugin::Init()
{
this->jointExplicit = this->model->GetJoint(this->jointExplicitName);
/* this->jointImplicit->SetStiffnessDamping(0, this->kpImplicit,
this->kdImplicit); */
this->updateConnection = event::Events::ConnectWorldUpdateBegin(
boost::bind(&SpringPlugin::ExplicitUpdate, this));
}
/////////////////////////////////////////////////
void SpringPlugin::ExplicitUpdate()
{
common::Time currTime = this->model->GetWorld()->GetSimTime();
common::Time stepTime = currTime - this->prevUpdateTime;
this->prevUpdateTime = currTime;
double pos = this->jointExplicit->GetAngle(0).Radian();
double vel = this->jointExplicit->GetVelocity(0);
double force = -this->kpExplicit * pos
-this->kdExplicit * vel;
this->jointExplicit->SetForce(0, force);
}
/*
* Copyright (C) 2012 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef __GAZEBO_SPRING_TEST_PLUGIN_HH__
#define __GAZEBO_SPRING_TEST_PLUGIN_HH__
#include <string>
#include "gazebo/common/Plugin.hh"
#include "gazebo/physics/physics.hh"
#include "gazebo/util/system.hh"
namespace gazebo
{
class GAZEBO_VISIBLE SpringPlugin : public ModelPlugin
{
public: SpringPlugin();
public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
public: virtual void Init();
private: void ExplicitUpdate();
private: event::ConnectionPtr updateConnection;
private: physics::ModelPtr model;
private: common::Time prevUpdateTime;
private: physics::JointPtr jointExplicit;
private: std::string jointExplicitName;
/// \brief simulate spring/damper with ExplicitUpdate function
private: double kpExplicit;
/// \brief simulate spring/damper with ExplicitUpdate function
private: double kdExplicit;
};
}
#endif
talos.srdf
\ No newline at end of file
......@@ -162,7 +162,7 @@
<joint name="torso_2_joint" value="0.006761" />
</group_state>
<rotor_params>
<joint name="arm_left_1_joint" mass="1e-5" gear_ratio="100." />
<joint name="arm_left_2_joint" mass="1e-5" gear_ratio="100." />
......@@ -195,7 +195,7 @@
<joint name="torso_1_joint" mass="1e-5" gear_ratio="100." />
<joint name="torso_2_joint" mass="1e-5" gear_ratio="100." />
</rotor_params>
<!--
Talos Specificities.
......@@ -682,17 +682,17 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant.
<disable_collisions link1="wrist_right_ft_link" link2="wrist_right_ft_tool_link" reason="Adjacent" />
<gripper name="left_gripper" clearance="0.03">
<gripper name="left_gripper" clearance="0.07">
<position> 0 0 -0.13 0.707106 0 0.707106 0</position>
<link name="gripper_left_base_link" />
<joint name="gripper_left_joint" />
<torque_constant value="48e-3" unit="N.m/A"/>
</gripper>
<gripper name="right_gripper" clearance="0.03">
<gripper name="right_gripper" clearance="0.07">
<position> 0 0 -0.13 0 -0.707106 0 0.707106 </position>
<link name="gripper_right_base_link" />
<joint name="gripper_right_joint" />
<torque_constant value="48e-3" unit="N.m/A"/>
</gripper>
</gripper>
</robot>
This diff is collapsed.
......@@ -35,4 +35,4 @@
</xacro:macro>
</robot>
\ No newline at end of file
</robot>
......@@ -23,4 +23,3 @@
</transmission>
</xacro:macro>
</robot>
......@@ -57,7 +57,7 @@
<child link="leg_${prefix}_1_link_passive"/>
<origin xyz="0.0 0.0 0.0"
rpy="0.00000 0.00000 0.00000"/>
<axis xyz="0 1 0" />
<axis xyz="1 0 0" />
<limit lower="${(-180.0)*deg_to_rad}" upper="${(180.0)*deg_to_rad}" effort="100" velocity="3.87" />
<dynamics friction="970.0" damping="0.0"/>
</joint>
......
talos_full_v2_with_lidar.urdf
\ No newline at end of file
......@@ -27,5 +27,3 @@
<xacro:property name="cal_head_mount_xtion_yaw" value="0.0" />
</robot>
......@@ -2188,8 +2188,8 @@
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
</collision>
-->
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
......@@ -2514,8 +2514,8 @@
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
</collision>
-->
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
......