新增gazebo_demo1功能包
parent
65b4603e1c
commit
5f068c763c
|
@ -0,0 +1,42 @@
|
||||||
|
cmake_minimum_required(VERSION 2.8.3)
|
||||||
|
|
||||||
|
project(gazebo_demo1)
|
||||||
|
|
||||||
|
add_compile_options(-std=c++11)
|
||||||
|
|
||||||
|
find_package(catkin REQUIRED)
|
||||||
|
|
||||||
|
catkin_package()
|
||||||
|
|
||||||
|
find_package(catkin REQUIRED COMPONENTS
|
||||||
|
roslaunch
|
||||||
|
controller_manager
|
||||||
|
gazebo_ros
|
||||||
|
gazebo_ros_control
|
||||||
|
joint_state_publisher
|
||||||
|
robot_state_publisher
|
||||||
|
roscpp
|
||||||
|
rospy
|
||||||
|
rviz
|
||||||
|
xacro
|
||||||
|
kdl_parser
|
||||||
|
tf
|
||||||
|
sensor_msgs
|
||||||
|
std_msgs
|
||||||
|
trac_ik_lib
|
||||||
|
serial
|
||||||
|
)
|
||||||
|
|
||||||
|
include_directories(
|
||||||
|
include
|
||||||
|
${catkin_INCLUDE_DIRS}
|
||||||
|
${orocos_kdl_INCLUDE_DIRS}
|
||||||
|
)
|
||||||
|
|
||||||
|
add_executable(gazebo_demo1 src/gazebo_demo1.cpp)
|
||||||
|
target_link_libraries(gazebo_demo1 ${catkin_LIBRARIES} ${orocos_kdl_LIBRARIES})
|
||||||
|
|
||||||
|
foreach(dir config launch meshes urdf)
|
||||||
|
install(DIRECTORY ${dir}/
|
||||||
|
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
|
||||||
|
endforeach(dir)
|
|
@ -0,0 +1,53 @@
|
||||||
|
gazebo_demo1:
|
||||||
|
|
||||||
|
# Publish all joint states -----------------------------------
|
||||||
|
|
||||||
|
joint_state_controller:
|
||||||
|
|
||||||
|
type: joint_state_controller/JointStateController
|
||||||
|
|
||||||
|
publish_rate: 50
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
# Position Controllers ---------------------------------------
|
||||||
|
|
||||||
|
lf_position_con:
|
||||||
|
|
||||||
|
type: position_controllers/JointPositionController
|
||||||
|
|
||||||
|
joint: LF_JOINT
|
||||||
|
|
||||||
|
#pid: {p: 1.0, i: 0.01, d: 0.0}
|
||||||
|
|
||||||
|
lb_position_con:
|
||||||
|
|
||||||
|
type: position_controllers/JointPositionController
|
||||||
|
|
||||||
|
joint: LB_JOINT
|
||||||
|
|
||||||
|
#pid: {p: 1.0, i: 0.01, d: 0.0}
|
||||||
|
|
||||||
|
rf_position_con:
|
||||||
|
|
||||||
|
type: position_controllers/JointPositionController
|
||||||
|
|
||||||
|
joint: RF_JOINT
|
||||||
|
|
||||||
|
#pid: {p: 1.0, i: 0.01, d: 0.0}
|
||||||
|
|
||||||
|
rb_position_con:
|
||||||
|
|
||||||
|
type: position_controllers/JointPositionController
|
||||||
|
|
||||||
|
joint: RB_JOINT
|
||||||
|
|
||||||
|
#pid: {p: 1.0, i: 0.01, d: 0.0}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
gazebo_demo1/gazebo_ros_control/pid_gains:
|
||||||
|
LF_JOINT: {p: 1.0, i: 0.0, d: 0.0}
|
||||||
|
LB_JOINT: {p: 1.0, i: 0.0, d: 0.0}
|
||||||
|
RF_JOINT: {p: 1.0, i: 0.0, d: 0.0}
|
||||||
|
RB_JOINT: {p: 1.0, i: 0.0, d: 0.0}
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,10 @@
|
||||||
|
<launch>
|
||||||
|
<arg name="model" />
|
||||||
|
<arg name="gui" default="true" />
|
||||||
|
<param name="robot_description" textfile="$(find gazebo_demo1)/urdf/gazebo_demo1.urdf" />
|
||||||
|
<param name="use_gui" value="$(arg gui)" />
|
||||||
|
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
|
||||||
|
|
||||||
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
|
||||||
|
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find gazebo_demo1)/urdf.rviz" />
|
||||||
|
</launch>
|
|
@ -0,0 +1,43 @@
|
||||||
|
<launch>
|
||||||
|
|
||||||
|
<param name="robot_description" command="$(find xacro)/xacro $(find gazebo_demo1)/urdf/gazebo_demo1.urdf.xacro" />
|
||||||
|
|
||||||
|
<!-- these are the arguments you can pass this launch file, for example paused:=true -->
|
||||||
|
<arg name="paused" default="false"/>
|
||||||
|
<arg name="use_sim_time" default="true"/>
|
||||||
|
<arg name="gui" default="true"/>
|
||||||
|
<arg name="headless" default="false"/>
|
||||||
|
<arg name="debug" default="false"/>
|
||||||
|
|
||||||
|
<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
|
||||||
|
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||||
|
<arg name="world_name" value="$(find gazebo_demo1)/worlds/gazebo_demo1.world"/>
|
||||||
|
<arg name="debug" value="$(arg debug)" />
|
||||||
|
<arg name="gui" value="$(arg gui)" />
|
||||||
|
<arg name="paused" value="$(arg paused)"/>
|
||||||
|
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
|
||||||
|
<arg name="headless" value="$(arg headless)"/>
|
||||||
|
</include>
|
||||||
|
|
||||||
|
|
||||||
|
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
|
||||||
|
args="-urdf -model myrobot -param robot_description"/>
|
||||||
|
|
||||||
|
|
||||||
|
<rosparam file="$(find gazebo_demo1)/config/joint_names_gazebo_demo1.yaml" command="load"/>
|
||||||
|
|
||||||
|
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
|
||||||
|
output="screen" ns="/gazebo_demo1" args="lf_position_con
|
||||||
|
lb_position_con
|
||||||
|
rf_position_con
|
||||||
|
rb_position_con
|
||||||
|
"/>
|
||||||
|
|
||||||
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
|
||||||
|
respawn="false" output="screen">
|
||||||
|
<remap from="/joint_states" to="/gazebo_demo1/joint_states" />
|
||||||
|
</node>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
</launch>
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,21 @@
|
||||||
|
<package format="2">
|
||||||
|
<name>gazebo_demo1</name>
|
||||||
|
<version>1.0.0</version>
|
||||||
|
<description>
|
||||||
|
<p>URDF Description package for gazebo_demo1</p>
|
||||||
|
<p>This package contains configuration data, 3D models and launch files
|
||||||
|
for gazebo_demo1 robot</p>
|
||||||
|
</description>
|
||||||
|
<author>TODO</author>
|
||||||
|
<maintainer email="TODO@email.com" />
|
||||||
|
<license>BSD</license>
|
||||||
|
<buildtool_depend>catkin</buildtool_depend>
|
||||||
|
<depend>roslaunch</depend>
|
||||||
|
<depend>robot_state_publisher</depend>
|
||||||
|
<depend>rviz</depend>
|
||||||
|
<depend>joint_state_publisher</depend>
|
||||||
|
<depend>gazebo</depend>
|
||||||
|
<export>
|
||||||
|
<architecture_independent />
|
||||||
|
</export>
|
||||||
|
</package>
|
|
@ -0,0 +1,49 @@
|
||||||
|
#include "ros/ros.h"
|
||||||
|
#include "std_msgs/Float64.h"
|
||||||
|
#include <sstream>
|
||||||
|
|
||||||
|
int main(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
setlocale(LC_ALL,"");
|
||||||
|
ros::init(argc,argv,"control_gazebo_demo1");
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
ros::Publisher pub_lf = nh.advertise<std_msgs::Float64>("/gazebo_demo1/lf_position_con/command",10);
|
||||||
|
ros::Publisher pub_lb = nh.advertise<std_msgs::Float64>("/gazebo_demo1/lb_position_con/command",10);
|
||||||
|
ros::Publisher pub_rf = nh.advertise<std_msgs::Float64>("/gazebo_demo1/rf_position_con/command",10);
|
||||||
|
ros::Publisher pub_rb = nh.advertise<std_msgs::Float64>("/gazebo_demo1/rb_position_con/command",10);
|
||||||
|
std_msgs::Float64 control_gazebo_demo1;
|
||||||
|
control_gazebo_demo1.data=0.0;
|
||||||
|
bool flag=0;//0weizeng 1weijian
|
||||||
|
ros::Rate r(15);
|
||||||
|
while (ros::ok())
|
||||||
|
{
|
||||||
|
|
||||||
|
pub_lf.publish(control_gazebo_demo1);
|
||||||
|
pub_lb.publish(control_gazebo_demo1);
|
||||||
|
pub_rf.publish(control_gazebo_demo1);
|
||||||
|
pub_rb.publish(control_gazebo_demo1);
|
||||||
|
control_gazebo_demo1.data+=0.1;
|
||||||
|
r.sleep();
|
||||||
|
|
||||||
|
/*
|
||||||
|
for(control_gazebo_demo.data=0.0;control_gazebo_demo.data<=1.5;control_gazebo_demo.data+=0.01)
|
||||||
|
{
|
||||||
|
pub.publish(control_gazebo_demo);
|
||||||
|
|
||||||
|
ROS_INFO("发送的消息:%f",control_gazebo_demo);
|
||||||
|
r.sleep();
|
||||||
|
}
|
||||||
|
|
||||||
|
for(control_gazebo_demo.data=1.5;control_gazebo_demo.data>=0.0;control_gazebo_demo.data-=0.01)
|
||||||
|
{
|
||||||
|
pub.publish(control_gazebo_demo);
|
||||||
|
|
||||||
|
ROS_INFO("发送的消息:%f",control_gazebo_demo);
|
||||||
|
r.sleep();
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
|
ros::spinOnce();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
|
@ -0,0 +1,342 @@
|
||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
|
||||||
|
Commit Version: 1.5.1-0-g916b5db Build Version: 1.5.7152.31018
|
||||||
|
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
|
||||||
|
<robot
|
||||||
|
name="gazebo_demo1">
|
||||||
|
|
||||||
|
<link
|
||||||
|
name="base_link">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="-6.0445212263786E-18 1.39257863414922E-18 -2.20581496680807E-19"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.468" />
|
||||||
|
<inertia
|
||||||
|
ixx="0.0001443"
|
||||||
|
ixy="-1.53384791846956E-20"
|
||||||
|
ixz="-1.37563571644961E-21"
|
||||||
|
iyy="0.0003939"
|
||||||
|
iyz="-1.29382985829106E-37"
|
||||||
|
izz="0.0005304" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/base_link.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/base_link.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link
|
||||||
|
name="LF_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.59413400484866E-18 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.20998908503938E-22"
|
||||||
|
ixz="-1.75453282727152E-23"
|
||||||
|
iyy="7.38080724035423E-07"
|
||||||
|
iyz="8.06501097239194E-25"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="LF_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="0.045 0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="LF_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
<link
|
||||||
|
name="LB_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.90361538571609E-18 6.93889390390723E-18"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.10469815160512E-22"
|
||||||
|
ixz="3.53711447230329E-24"
|
||||||
|
iyy="7.38080724035424E-07"
|
||||||
|
iyz="5.37667398159464E-25"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="LB_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="-0.045 0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="LB_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
<link
|
||||||
|
name="RF_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.85843759880028E-18 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.5173510835766E-22"
|
||||||
|
ixz="-9.00355753711158E-24"
|
||||||
|
iyy="7.38080724035423E-07"
|
||||||
|
iyz="-3.49483808803654E-24"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="RF_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="0.045 -0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="RF_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
</joint>
|
||||||
|
<link
|
||||||
|
name="RB_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.6227366665734E-18 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.36659023251123E-22"
|
||||||
|
ixz="1.17764472964423E-23"
|
||||||
|
iyy="7.38080724035423E-07"
|
||||||
|
iyz="-1.6130021944784E-24"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="RB_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="-0.045 -0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="RB_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<gazebo reference="base_link">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="LF_LINK">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="LB_LINK">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="RF_LINK">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="RB_LINK">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<transmission name="LF_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="LF_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="LF_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="LB_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="LB_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="LB_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="RF_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="RF_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="RF_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="RB_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="RB_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="RB_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||||
|
<robotNamespace>/gazebo_demo1</robotNamespace>
|
||||||
|
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||||
|
<legacyModeNS>true</legacyModeNS>
|
||||||
|
</plugin>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
</robot>
|
|
@ -0,0 +1,342 @@
|
||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
|
||||||
|
Commit Version: 1.5.1-0-g916b5db Build Version: 1.5.7152.31018
|
||||||
|
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
|
||||||
|
<robot
|
||||||
|
name="gazebo_demo1">
|
||||||
|
|
||||||
|
<link
|
||||||
|
name="base_link">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="-6.0445212263786E-18 1.39257863414922E-18 -2.20581496680807E-19"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.468" />
|
||||||
|
<inertia
|
||||||
|
ixx="0.0001443"
|
||||||
|
ixy="-1.53384791846956E-20"
|
||||||
|
ixz="-1.37563571644961E-21"
|
||||||
|
iyy="0.0003939"
|
||||||
|
iyz="-1.29382985829106E-37"
|
||||||
|
izz="0.0005304" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/base_link.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/base_link.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link
|
||||||
|
name="LF_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.59413400484866E-18 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.20998908503938E-22"
|
||||||
|
ixz="-1.75453282727152E-23"
|
||||||
|
iyy="7.38080724035423E-07"
|
||||||
|
iyz="8.06501097239194E-25"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="LF_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="0.045 0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="LF_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
<link
|
||||||
|
name="LB_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.90361538571609E-18 6.93889390390723E-18"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.10469815160512E-22"
|
||||||
|
ixz="3.53711447230329E-24"
|
||||||
|
iyy="7.38080724035424E-07"
|
||||||
|
iyz="5.37667398159464E-25"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="LB_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="-0.045 0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="LB_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
<link
|
||||||
|
name="RF_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.85843759880028E-18 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.5173510835766E-22"
|
||||||
|
ixz="-9.00355753711158E-24"
|
||||||
|
iyy="7.38080724035423E-07"
|
||||||
|
iyz="-3.49483808803654E-24"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="RF_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="0.045 -0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="RF_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
</joint>
|
||||||
|
<link
|
||||||
|
name="RB_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.6227366665734E-18 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.36659023251123E-22"
|
||||||
|
ixz="1.17764472964423E-23"
|
||||||
|
iyy="7.38080724035423E-07"
|
||||||
|
iyz="-1.6130021944784E-24"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="RB_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="-0.045 -0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="RB_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<gazebo reference="base_link">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="LF_LINK">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="LB_LINK">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="RF_LINK">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="RB_LINK">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<transmission name="LF_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="LF_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="LF_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="LB_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="LB_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="LB_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="RF_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="RF_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="RF_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="RB_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="RB_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="RB_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||||
|
<robotNamespace>/gazebo_demo1</robotNamespace>
|
||||||
|
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||||
|
<legacyModeNS>true</legacyModeNS>
|
||||||
|
</plugin>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
</robot>
|
|
@ -0,0 +1,362 @@
|
||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
|
||||||
|
Commit Version: 1.5.1-0-g916b5db Build Version: 1.5.7152.31018
|
||||||
|
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
|
||||||
|
<robot
|
||||||
|
name="gazebo_demo1">
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||||
|
<robotNamespace>/gazebo_demo1</robotNamespace>
|
||||||
|
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||||
|
<legacyModeNS>true</legacyModeNS>
|
||||||
|
</plugin>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<link
|
||||||
|
name="base_link">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="-6.0445212263786E-18 1.39257863414922E-18 -2.20581496680807E-19"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.468" />
|
||||||
|
<inertia
|
||||||
|
ixx="0.0001443"
|
||||||
|
ixy="-1.53384791846956E-20"
|
||||||
|
ixz="-1.37563571644961E-21"
|
||||||
|
iyy="0.0003939"
|
||||||
|
iyz="-1.29382985829106E-37"
|
||||||
|
izz="0.0005304" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/base_link.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/base_link.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link
|
||||||
|
name="LF_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.59413400484866E-18 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.20998908503938E-22"
|
||||||
|
ixz="-1.75453282727152E-23"
|
||||||
|
iyy="7.38080724035423E-07"
|
||||||
|
iyz="8.06501097239194E-25"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="LF_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="0.045 0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="LF_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
<limit effort="0.2" velocity="10" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
<link
|
||||||
|
name="LB_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.90361538571609E-18 6.93889390390723E-18"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.10469815160512E-22"
|
||||||
|
ixz="3.53711447230329E-24"
|
||||||
|
iyy="7.38080724035424E-07"
|
||||||
|
iyz="5.37667398159464E-25"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/LB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="LB_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="-0.045 0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="LB_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
<limit effort="0.2" velocity="10" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
<link
|
||||||
|
name="RF_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.85843759880028E-18 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.5173510835766E-22"
|
||||||
|
ixz="-9.00355753711158E-24"
|
||||||
|
iyy="7.38080724035423E-07"
|
||||||
|
iyz="-3.49483808803654E-24"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RF_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="RF_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="0.045 -0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="RF_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
<limit effort="0.2" velocity="10" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
<link
|
||||||
|
name="RB_LINK">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.01 -1.6227366665734E-18 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="0.0108630528372501" />
|
||||||
|
<inertia
|
||||||
|
ixx="1.06775440310417E-07"
|
||||||
|
ixy="1.36659023251123E-22"
|
||||||
|
ixz="1.17764472964423E-23"
|
||||||
|
iyy="7.38080724035423E-07"
|
||||||
|
iyz="-1.6130021944784E-24"
|
||||||
|
izz="7.99593444190632E-07" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.529411764705882 0.549019607843137 0.549019607843137 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo1/meshes/RB_LINK.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
</link>
|
||||||
|
<joint
|
||||||
|
name="RB_JOINT"
|
||||||
|
type="continuous">
|
||||||
|
<origin
|
||||||
|
xyz="-0.045 -0.0325 0"
|
||||||
|
rpy="1.5708 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="RB_LINK" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
<dynamic damping="0.7" friction="0.5" />
|
||||||
|
<limit effort="0.2" velocity="10" />
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<gazebo reference="base_link">
|
||||||
|
<mu>0.2</mu>
|
||||||
|
<mu2>0.2</mu2>
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="LF_LINK">
|
||||||
|
<mu1>1</mu1>
|
||||||
|
<mu2>1</mu2>
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="LB_LINK">
|
||||||
|
<mu1>1</mu1>
|
||||||
|
<mu2>1</mu2>
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="RF_LINK">
|
||||||
|
<mu1>1</mu1>
|
||||||
|
<mu2>1</mu2>
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<gazebo reference="RB_LINK">
|
||||||
|
<mu1>1</mu1>
|
||||||
|
<mu2>1</mu2>
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
<transmission name="LF_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="LF_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="LF_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="LB_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="LB_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="LB_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="RF_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="RF_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="RF_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="RB_JOINT_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="RB_JOINT">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="RB_JOINT_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
</robot>
|
|
@ -0,0 +1,6 @@
|
||||||
|
Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
|
||||||
|
base_link,-6.0445212263786E-18,1.39257863414922E-18,-2.20581496680807E-19,0,0,0,0.468,0.0001443,-1.53384791846956E-20,-1.37563571644961E-21,0.0003939,-1.29382985829106E-37,0.0005304,0,0,0,0,0,0,package://gazebo_demo2/meshes/base_link.STL,0.529411764705882,0.549019607843137,0.549019607843137,1,0,0,0,0,0,0,package://gazebo_demo2/meshes/base_link.STL,,零件-1,坐标系1,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
|
||||||
|
LF_LINK,0.01,-1.59413400484866E-18,0,0,0,0,0.0108630528372501,1.06775440310417E-07,1.20998908503938E-22,-1.75453282727152E-23,7.38080724035423E-07,8.06501097239194E-25,7.99593444190632E-07,0,0,0,0,0,0,package://gazebo_demo2/meshes/LF_LINK.STL,0.529411764705882,0.549019607843137,0.549019607843137,1,0,0,0,0,0,0,package://gazebo_demo2/meshes/LF_LINK.STL,,tui-1,坐标系2,基准轴2,LF_JOINT,continuous,0.045,0.0325,0,1.5708,0,0,base_link,0,0,1,1,1,,,,,,,,,,
|
||||||
|
LB_LINK,0.01,-1.90361538571609E-18,6.93889390390723E-18,0,0,0,0.0108630528372501,1.06775440310417E-07,1.10469815160512E-22,3.53711447230329E-24,7.38080724035424E-07,5.37667398159464E-25,7.99593444190632E-07,0,0,0,0,0,0,package://gazebo_demo2/meshes/LB_LINK.STL,0.529411764705882,0.549019607843137,0.549019607843137,1,0,0,0,0,0,0,package://gazebo_demo2/meshes/LB_LINK.STL,,tui-2,坐标系3,基准轴3,LB_JOINT,continuous,-0.045,0.0325,0,1.5708,0,0,base_link,0,0,1,1,1,,,,,,,,,,
|
||||||
|
RF_LINK,0.01,-1.85843759880028E-18,0,0,0,0,0.0108630528372501,1.06775440310417E-07,1.5173510835766E-22,-9.00355753711158E-24,7.38080724035423E-07,-3.49483808803654E-24,7.99593444190632E-07,0,0,0,0,0,0,package://gazebo_demo2/meshes/RF_LINK.STL,0.529411764705882,0.549019607843137,0.549019607843137,1,0,0,0,0,0,0,package://gazebo_demo2/meshes/RF_LINK.STL,,tui-4,坐标系4,基准轴4,RF_JOINT,continuous,0.045,-0.0325,0,1.5708,0,0,base_link,0,0,1,1,1,,,,,,,,,,
|
||||||
|
RB_LINK,0.01,-1.6227366665734E-18,0,0,0,0,0.0108630528372501,1.06775440310417E-07,1.36659023251123E-22,1.17764472964423E-23,7.38080724035423E-07,-1.6130021944784E-24,7.99593444190632E-07,0,0,0,0,0,0,package://gazebo_demo2/meshes/RB_LINK.STL,0.529411764705882,0.549019607843137,0.549019607843137,1,0,0,0,0,0,0,package://gazebo_demo2/meshes/RB_LINK.STL,,tui-3,坐标系5,基准轴5,RB_JOINT,continuous,-0.045,-0.0325,0,1.5708,0,0,base_link,0,0,1,1,1,,,,,,,,,,
|
|
Loading…
Reference in New Issue