gazebo仿真第一个例程,单自由度机器人
commit
65b4603e1c
|
@ -0,0 +1,42 @@
|
||||||
|
cmake_minimum_required(VERSION 2.8.3)
|
||||||
|
|
||||||
|
project(gazebo_demo)
|
||||||
|
|
||||||
|
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_demo src/gazebo_demo.cpp)
|
||||||
|
target_link_libraries(gazebo_demo ${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,14 @@
|
||||||
|
gazebo_demo:
|
||||||
|
# Publish all joint states -----------------------------------
|
||||||
|
joint_state_controller:
|
||||||
|
type: joint_state_controller/JointStateController
|
||||||
|
publish_rate: 50
|
||||||
|
|
||||||
|
# Position Controllers ---------------------------------------
|
||||||
|
joint1_position_controller:
|
||||||
|
type: position_controllers/JointPositionController
|
||||||
|
joint: joint_1
|
||||||
|
#pid: {p: 100.0, i: 0.01, d: 10.0}
|
||||||
|
|
||||||
|
gazebo_demo/gazebo_ros_control/pid_gains:
|
||||||
|
joint_1: {p: 100.0, i: 0.0, d: 10.0}
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,26 @@
|
||||||
|
<launch>
|
||||||
|
<arg
|
||||||
|
name="model" />
|
||||||
|
<arg
|
||||||
|
name="gui"
|
||||||
|
default="False" />
|
||||||
|
<param
|
||||||
|
name="robot_description"
|
||||||
|
textfile="$(find gazebo_demo)/urdf/gazebo_demo.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_demo)/urdf.rviz" />
|
||||||
|
</launch>
|
|
@ -0,0 +1,37 @@
|
||||||
|
<launch>
|
||||||
|
|
||||||
|
<param name="robot_description" command="$(find xacro)/xacro $(find gazebo_demo)/urdf/gazebo_demo.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_demo)/worlds/gazebo_demo.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_demo)/config/joint_names_gazebo_demo.yaml" command="load"/>
|
||||||
|
|
||||||
|
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
|
||||||
|
output="screen" ns="/gazebo_demo" args="joint1_position_controller"/>
|
||||||
|
|
||||||
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
|
||||||
|
respawn="false" output="screen">
|
||||||
|
<remap from="/joint_states" to="/gazebo_demo/joint_states" />
|
||||||
|
</node>
|
||||||
|
|
||||||
|
|
||||||
|
</launch>
|
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,21 @@
|
||||||
|
<package format="2">
|
||||||
|
<name>gazebo_demo</name>
|
||||||
|
<version>1.0.0</version>
|
||||||
|
<description>
|
||||||
|
<p>URDF Description package for gazebo_demo</p>
|
||||||
|
<p>This package contains configuration data, 3D models and launch files
|
||||||
|
for gazebo_demo 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,39 @@
|
||||||
|
#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_demo");
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
ros::Publisher pub = nh.advertise<std_msgs::Float64>("/gazebo_demo/joint1_position_controller/command",10);
|
||||||
|
std_msgs::Float64 control_gazebo_demo;
|
||||||
|
control_gazebo_demo.data=0.0;
|
||||||
|
bool flag=0;//0weizeng 1weijian
|
||||||
|
ros::Rate r(50);
|
||||||
|
while (ros::ok())
|
||||||
|
{
|
||||||
|
|
||||||
|
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,3 @@
|
||||||
|
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,0,9.74542958129844E-19,-4.31390337655099E-18,0,0,0,6.99004365423729,0.0101938136624294,0,-3.37700910261971E-35,0.0101938136624294,-8.16962303997948E-35,0.00873755456779662,0,0,0,0,0,0,package://gazebo_demo/meshes/base_link.STL,0.537254901960784,0.349019607843137,0.337254901960784,1,0,0,0,0,0,0,package://gazebo_demo/meshes/base_link.STL,,gazebo_demo_part1-1,坐标系1,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
|
||||||
|
link_1,0.1,-1.86377227087894E-19,-1.38777878078145E-17,0,0,0,1.12492033114729,0.000798459868114599,1.67727625611222E-20,8.85083255431749E-21,0.00679752984625413,9.66746937132908E-21,0.00712727290972403,0,0,0,0,0,0,package://gazebo_demo/meshes/link_1.STL,1,1,1,0.32,0,0,0,0,0,0,package://gazebo_demo/meshes/link_1.STL,,gazebo_demo_part2-1,坐标系2,基准轴1,joint_1,revolute,0,0,0.075,0,0,0,base_link,0,0,-1,1,1,-1.57,1.57,,,,,,,,
|
|
|
@ -0,0 +1,133 @@
|
||||||
|
<?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_demo">
|
||||||
|
<link
|
||||||
|
name="base_link">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0 9.74542958129844E-19 -4.31390337655099E-18"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="6.99004365423729" />
|
||||||
|
<inertia
|
||||||
|
ixx="0.0101938136624294"
|
||||||
|
ixy="0"
|
||||||
|
ixz="-3.37700910261971E-35"
|
||||||
|
iyy="0.0101938136624294"
|
||||||
|
iyz="-8.16962303997948E-35"
|
||||||
|
izz="0.00873755456779662" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo/meshes/base_link.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="0.537254901960784 0.349019607843137 0.337254901960784 1" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo/meshes/base_link.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5"/>
|
||||||
|
</link>
|
||||||
|
<gazebo reference="base_link">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
<link
|
||||||
|
name="link_1">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0.1 -1.86377227087894E-19 -1.38777878078145E-17"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="1.12492033114729" />
|
||||||
|
<inertia
|
||||||
|
ixx="0.000798459868114599"
|
||||||
|
ixy="1.67727625611222E-20"
|
||||||
|
ixz="8.85083255431749E-21"
|
||||||
|
iyy="0.00679752984625413"
|
||||||
|
iyz="9.66746937132908E-21"
|
||||||
|
izz="0.00712727290972403" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo/meshes/link_1.STL" />
|
||||||
|
</geometry>
|
||||||
|
<material
|
||||||
|
name="">
|
||||||
|
<color
|
||||||
|
rgba="1 1 1 0.32" />
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="package://gazebo_demo/meshes/link_1.STL" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<dynamic damping="0.7" friction="0.5"/>
|
||||||
|
</link>
|
||||||
|
<gazebo reference="link_1">
|
||||||
|
<material>Gazebo/Black</material>
|
||||||
|
</gazebo>
|
||||||
|
<joint
|
||||||
|
name="joint_1"
|
||||||
|
type="revolute">
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0.075"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<parent
|
||||||
|
link="base_link" />
|
||||||
|
<child
|
||||||
|
link="link_1" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 -1" />
|
||||||
|
<limit
|
||||||
|
lower="-1.57"
|
||||||
|
upper="1.57"
|
||||||
|
effort="1"
|
||||||
|
velocity="10" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="joint_1_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="joint_1">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="joint_1_motor">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||||
|
<robotNamespace>/gazebo_demo</robotNamespace>
|
||||||
|
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||||
|
<legacyModeNS>true</legacyModeNS>
|
||||||
|
</plugin>
|
||||||
|
</gazebo>
|
||||||
|
|
||||||
|
</robot>
|
Loading…
Reference in New Issue