<!-- <test_depend>gtest</test_depend> -->
<buildtool_depend>catkin</buildtool_depend>
-
+ <run_depend>wam_description</run_depend>
+ <run_depend>wam_gazebo_ros_control</run_depend>
+ <run_depend>wam_controllers</run_depend>
+
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- You can specify that this package is a metapackage here: -->
<!-- Other tools can request additional information be placed here -->
</export>
-</package>
\ No newline at end of file
+</package>
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
-find_package(catkin REQUIRED)
+find_package(catkin REQUIRED COMPONENTS
+ controller_interface
+ control_msgs
+ urdf
+)
+find_package(cmake_modules REQUIRED)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
find_package(Eigen REQUIRED)
+find_package(orocos_kdl REQUIRED)
+find_package(kdl_parser REQUIRED)
## Uncomment this if the package has a setup.py. This macro ensures
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
-# LIBRARIES wam_controllers
-# CATKIN_DEPENDS other_catkin_pkg
+ LIBRARIES ${PROJECT_NAME}
+ CATKIN_DEPENDS controller_interface control_msgs urdf
# DEPENDS system_lib
- DEPENDS eigen
+ DEPENDS eigen orocos_kdl kdl_parser
)
###########
# add_dependencies(wam_controllers_node wam_controllers_generate_messages_cpp)
## Specify libraries to link a library or executable target against
-# target_link_libraries(wam_controllers_node
-# ${catkin_LIBRARIES}
-# )
+target_link_libraries(${PROJECT_NAME}
+ ${catkin_LIBRARIES}
+ ${orocos-kdl_LIBRARIES}
+ ${kdl_parser_LIBRARIES}
+)
#############
## Install ##
# )
## Mark executables and/or libraries for installation
-# install(TARGETS wam_controllers wam_controllers_node
-# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
+install(TARGETS ${PROJECT_NAME}
+ ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+ LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+ RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+)
## Mark cpp header files for installation
-# install(DIRECTORY include/${PROJECT_NAME}/
-# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
+install(DIRECTORY include/${PROJECT_NAME}/
+ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
-# )
+)
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
rostopic pub /wam/computed_torque_controller/command trajectory_msgs/JointTrajectoryPoint "[0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0]"
-Arguments are positions, velocities, accelerations, time from start in
+Arguments are positions, velocities, accelerations, effort, time from start in
seconds and nanoseconds.
Set starting position:
wam:
-
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 100
args="joint_state_controller computed_torque_controller"/>
<node name="robot_state_publisher" pkg="robot_state_publisher"
- type="state_publisher" />
+ type="state_publisher"
+ ns="/wam" />
</launch>
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/wam" args="joint_state_controller computed_torque_controller"/>
- <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
+ <node name="robot_state_publisher" pkg="robot_state_publisher"
+ type="state_publisher"
+ ns="/wam" />
</launch>
<!-- <test_depend>gtest</test_depend> -->
<buildtool_depend>catkin</buildtool_depend>
- <build_depend>wam_control_gazebo</build_depend>
+ <build_depend>wam_gazebo_ros_control</build_depend>
<build_depend>controller_interface</build_depend>
<build_depend>orocos_kdl</build_depend>
<build_depend>kdl_parser</build_depend>
<build_depend>trajectory_msgs</build_depend>
+ <build_depend>control_msgs</build_depend>
+ <build_depend>urdf</build_depend>
+ <build_depend>cmake_modules</build_depend>
-
+ <run_depend>cmake_modules</run_depend>
+ <run_depend>controller_interface</run_depend>
+ <run_depend>controller_manager</run_depend>
+ <run_depend>control_msgs</run_depend>
<run_depend> joint_state_controller</run_depend>
+ <run_depend>urdf</run_depend>
+ <run_depend>kdl_parser</run_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
--- /dev/null
+#!/bin/bash
+
+rostopic pub /wam/computed_torque_controller/command \
+trajectory_msgs/JointTrajectoryPoint \
+"[0.0,-2.0,0.0,3.1,0.0,0.0,0.0]" \
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0]" "-1"
--- /dev/null
+#!/bin/bash
+
+rostopic pub /wam/computed_torque_controller/command \
+trajectory_msgs/JointTrajectoryPoint \
+"[0.0,0.75,0.0,1.5,0.0,0.9,0.0]" \
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0]" -1
trajectory_msgs/JointTrajectoryPoint \
"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
-"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0]" -1
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0]" -1
#!/bin/bash
rosservice call /gazebo/set_model_configuration wam joint \
-['wam_joint_1','wam_joint_2','wam_joint_3','wam_joint_4', \
-'wam_joint_5','wam_joint_6','wam_joint_7'] \
-[0.0,-2.0,0.0,3.1,0.0,0.0,0.0]
+"['wam_joint_1','wam_joint_2','wam_joint_3','wam_joint_4','wam_joint_5','wam_joint_6','wam_joint_7']" \
+"[0.0,-2.0,0.0,3.1,0.0,0.0,0.0]"
rostopic pub /wam/computed_torque_controller/command \
trajectory_msgs/JointTrajectoryPoint \
"[0.0,-2.0,0.0,3.1,0.0,0.0,0.0]" \
"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
-"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0]" -1
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0]" "-1"
#!/bin/bash
rosservice call /gazebo/set_model_configuration wam joint \
-['wam_joint_1','wam_joint_2','wam_joint_3','wam_joint_4', \
-'wam_joint_5','wam_joint_6','wam_joint_7'] \
-[0.0,0.75,0.0,1.5,0.0,0.9,0.0]
+"['wam_joint_1','wam_joint_2','wam_joint_3','wam_joint_4', \
+'wam_joint_5','wam_joint_6','wam_joint_7']" \
+"[0.0,0.75,0.0,1.5,0.0,0.9,0.0]"
rostopic pub /wam/computed_torque_controller/command \
trajectory_msgs/JointTrajectoryPoint \
"[0.0,0.75,0.0,1.5,0.0,0.9,0.0]" \
"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
-"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0]" -1
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" \
+"[0.0, 0.0]" -1
#include <kdl_parser/kdl_parser.hpp>
#include <kdl/chainidsolver_recursive_newton_euler.hpp>
-#define Ts 5.0
+#define Ts 0.5
#define Xi 1.0
#define Wn (4.0/Ts/Xi)
}
}
-PLUGINLIB_DECLARE_CLASS(wam_controllers,ComputedTorqueController,
- wam_controllers::ComputedTorqueController,controller_interface::ControllerBase)
+PLUGINLIB_EXPORT_CLASS(wam_controllers::ComputedTorqueController,controller_interface::ControllerBase)
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
+install(DIRECTORY launch
+ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
+
+install(DIRECTORY meshes
+ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
+
+install(DIRECTORY xacro
+ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
+
#############
## Testing ##
#############
<launch>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find wam_description)/xacro/wam.urdf.xacro'" />
- <node name="spawn_wam_object" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model wam" respawn="false" output="screen" />
+ <node name="wam_spawner" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model wam" respawn="false" output="screen" />
</launch>
<!-- Start Gazebo -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="paused" value="$(arg paused)"/>
+ <arg name="world_name" value="worlds/empty_sky.world" />
</include>
<include file="$(find wam_description)/launch/wam.launch"/>
<launch>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find wam_description)/xacro/wam_table.urdf.xacro'" />
- <node name="spawn_wam_object" pkg="gazebo" type="spawn_model" args="-urdf -param robot_description -model wam" respawn="false" output="screen" />
+ <node name="wam_spawner" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model wam" respawn="false" output="screen" />
</launch>
<arg name="paused" default="false"/>
<!-- Start Gazebo -->
- <include file="$(find gazebo_worlds)/launch/empty_world.launch">
+ <include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="paused" value="$(arg paused)"/>
+ <arg name="world_name" value="worlds/empty_sky.world" />
</include>
<include file="$(find wam_description)/launch/wam_table.launch"/>
--- /dev/null
+<?xml version="1.0"?>
+
+<robot name="table" xmlns:xacro="http://ros.org/wiki/xacro" >
+
+ <property name="table_height" value="0.55" />
+ <property name="table_width" value="1.0" />
+ <property name="table_depth" value="2.0" />
+ <property name="leg_radius" value="0.02" />
+ <property name="table_x" value="0.98" />
+ <property name="table_y" value="0.0" />
+ <property name="table_z" value="0.0" />
+
+ <property name="table_top_thickness" value="0.05"/>
+
+ <property name="M_PI" value="3.1415926535897931" />
+
+
+ <!-- tabletop height is .55+.01+.025=.585 -->
+ <link name="table_top_link">
+ <inertial>
+ <mass value="1.0" />
+ <origin xyz="${table_x} ${table_y} ${table_z+table_height-table_top_thickness/2}" />
+ <inertia ixx="1" ixy="0" ixz="0"
+ iyy="1" iyz="0"
+ izz="1" />
+ </inertial>
+ <visual>
+ <origin xyz="${table_x} ${table_y} ${table_z+table_height-table_top_thickness/2}" />
+ <geometry>
+ <box size="${table_width} ${table_depth} ${table_top_thickness}" />
+ </geometry>
+ </visual>
+ <collision>
+ <origin xyz="${table_x} ${table_y} ${table_z+table_height-table_top_thickness/2}" />
+ <geometry>
+ <box size="${table_width} ${table_depth} ${table_top_thickness}" />
+ </geometry>
+ </collision>
+ </link>
+ <gazebo reference="table_top_link">
+ <material>Gazebo/Wood</material>
+ <mu1>50.0</mu1>
+ <mu2>50.0</mu2>
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ </gazebo>
+
+ <joint name="leg1_joint" type="fixed" >
+ <parent link="table_top_link" />
+ <origin xyz="${table_x+table_width/2} ${table_y+table_depth/2} ${table_z+table_height}" rpy="0 0 0" />
+ <child link="leg1_link" />
+ </joint>
+ <link name="leg1_link">
+ <inertial>
+ <mass value="1.0" />
+ <origin xyz="0 0 ${-table_height/2}" />
+ <inertia ixx="0.1" ixy="0" ixz="0"
+ iyy="0.1" iyz="0"
+ izz="0.01" />
+ </inertial>
+ <visual>
+ <origin xyz="0.0 0.0 ${-table_height/2}" rpy="0 0 0" />
+ <geometry>
+ <cylinder radius="${leg_radius}" length="${table_height}" />
+ </geometry>
+ </visual>
+ <collision>
+ <origin xyz="0.0 0.0 ${-table_height/2}" rpy="0.0 0.0 0.0" />
+ <geometry>
+ <cylinder radius="${leg_radius}" length="${table_height}" />
+ </geometry>
+ </collision>
+ </link>
+ <gazebo reference="leg1_link">
+ <material>Gazebo/Red</material>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <kp>10000000.0</kp>
+ <kd>1.0</kd>
+ <!-- <selfCollide>true</selfCollide> -->
+ </gazebo>
+
+ <joint name="leg2_joint" type="fixed" >
+ <parent link="table_top_link" />
+ <origin xyz="${table_x-table_width/2} ${table_y+table_depth/2} ${table_z+table_height}" rpy="0 0 0" />
+ <child link="leg2_link" />
+ </joint>
+ <link name="leg2_link">
+ <inertial>
+ <mass value="1.0" />
+ <origin xyz="0 0 ${-table_height/2}" />
+ <inertia ixx="0.1" ixy="0" ixz="0"
+ iyy="0.1" iyz="0"
+ izz="0.01" />
+ </inertial>
+ <visual>
+ <origin xyz="0.0 0.0 ${-table_height/2}" rpy="0 0 0" />
+ <geometry>
+ <cylinder radius="${leg_radius}" length="${table_height}" />
+ </geometry>
+ </visual>
+ <collision>
+ <origin xyz="0.0 0.0 ${-table_height/2}" rpy="0.0 0.0 0.0" />
+ <geometry>
+ <cylinder radius="${leg_radius}" length="${table_height}" />
+ </geometry>
+ </collision>
+ </link>
+ <gazebo reference="leg2_link">
+ <material>Gazebo/Red</material>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <kp>10000000.0</kp>
+ <kd>1.0</kd>
+ <!-- <selfCollide>true</selfCollide> -->
+ </gazebo>
+
+ <joint name="leg3_joint" type="fixed" >
+ <parent link="table_top_link" />
+ <origin xyz="${table_x+table_width/2} ${table_y-table_depth/2} ${table_z+table_height}" rpy="0 0 0" />
+ <child link="leg3_link" />
+ </joint>
+ <link name="leg3_link">
+ <inertial>
+ <mass value="1.0" />
+ <origin xyz="0 0 ${-table_height/2}" />
+ <inertia ixx="0.1" ixy="0" ixz="0"
+ iyy="0.1" iyz="0"
+ izz="0.01" />
+ </inertial>
+ <visual>
+ <origin xyz="0.0 0.0 ${-table_height/2}" rpy="0 0 0" />
+ <geometry>
+ <cylinder radius="${leg_radius}" length="${table_height}" />
+ </geometry>
+ </visual>
+ <collision>
+ <origin xyz="0.0 0.0 ${-table_height/2}" rpy="0.0 0.0 0.0" />
+ <geometry>
+ <cylinder radius="${leg_radius}" length="${table_height}" />
+ </geometry>
+ </collision>
+ </link>
+ <gazebo reference="leg3_link">
+ <material>Gazebo/Red</material>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <kp>10000000.0</kp>
+ <kd>1.0</kd>
+ <!-- <selfCollide>true</selfCollide> -->
+ </gazebo>
+
+ <joint name="leg4_joint" type="fixed" >
+ <parent link="table_top_link" />
+ <origin xyz="${table_x-table_width/2} ${table_y-table_depth/2} ${table_z+table_height}" rpy="0 0 0" />
+ <child link="leg4_link" />
+ </joint>
+ <link name="leg4_link">
+ <inertial>
+ <mass value="1.0" />
+ <origin xyz="0 0 ${-table_height/2}" />
+ <inertia ixx="0.1" ixy="0" ixz="0"
+ iyy="0.1" iyz="0"
+ izz="0.01" />
+ </inertial>
+ <visual>
+ <origin xyz="0.0 0.0 ${-table_height/2}" rpy="0 0 0" />
+ <geometry>
+ <cylinder radius="${leg_radius}" length="${table_height}" />
+ </geometry>
+ </visual>
+ <collision>
+ <origin xyz="0.0 0.0 ${-table_height/2}" rpy="0.0 0.0 0.0" />
+ <geometry>
+ <cylinder radius="${leg_radius}" length="${table_height}" />
+ </geometry>
+ </collision>
+ </link>
+ <gazebo reference="leg4_link">
+ <material>Gazebo/Red</material>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <kp>10000000.0</kp>
+ <kd>1.0</kd>
+ <!-- <selfCollide>true</selfCollide> -->
+ </gazebo>
+ <gazebo>
+ <!-- <static>true</static> -->
+ <canonicalBody>table_top_link</canonicalBody>
+ </gazebo>
+
+
+</robot>
<?xml version="1.0"?>
-<robot name="wam"
- xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
- xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
- xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
- xmlns:xacro="http://ros.org/wiki/xacro">
-
+
+<robot name="wam" xmlns:xacro="http://ros.org/wiki/xacro">
+
<xacro:include filename="$(find wam_description)/xacro/wam_base.urdf.xacro" />
<xacro:include filename="$(find wam_description)/xacro/wam_j1.urdf.xacro" />
<xacro:include filename="$(find wam_description)/xacro/wam_j2.urdf.xacro" />
</xacro:wam_tool_plate>
<gazebo>
- <plugin name="ros_control" filename="libgazebo_ros_control_plugin.so">
- <ns>wam</ns>
- <robotSimType>wam_control_gazebo/RobotSimWam</robotSimType>
+ <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so" >
+ <robotNamespace>/wam</robotNamespace>
+
+ <!-- Custom plugin -->
+ <!-- robotSimType>wam_gazebo_ros_control/WamRobotHWSim</robotSimType -->
+
+ <!-- Default plugin -->
+ <!-- robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType -->
+
<controlPeriod>0.001</controlPeriod>
</plugin>
</gazebo>
+
</robot>
</link>
<gazebo reference="wam_link_base">
- <selfCollide>true</selfCollide>
- <material>Gazebo/Grey</material>
+ <!-- <selfCollide>true</selfCollide> -->
+ <material>Gazebo/White</material>
</gazebo>
<geometry name="wam_j1_collision">
<mesh filename="package://wam_description/meshes/wam1.stl" scale="1.0 1.0 1.0"/>
</geometry>
+ <!--
<contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+ -->
</collision>
</link>
<gazebo reference="wam_link_1">
- <material>Gazebo/Grey</material>
+ <material>Gazebo/White</material>
<selfCollide>true</selfCollide>
</gazebo>
<axis xyz="0 0 1"/>
<limit effort="30" lower="-2.6" upper="2.6" velocity="2.0"/>
<!-- <safety_controller k_velocity="0.5"/> -->
- <joint_properties damping="100.0" friction="1000.0" />
- <dynamics damping="1000"/>
+ <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
+ <dynamics damping="0.9" friction="${3.0/7}"/>
</joint>
- <transmission name="j1_transmission" type="pr2_mechanism_model/SimpleTransmission">
- <actuator name="j1"/>
- <joint name="wam_joint_1"/>
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
+ <transmission name="j1_transmission">
+ <type>transmission_interface/SimpleTransmission"</type>
+ <joint name="wam_joint_1">
+ <hardwareInterface>EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="j1">
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
</transmission>
</xacro:macro>
</link>
<gazebo reference="wam_link_2">
- <material>Gazebo/Grey</material>
+ <material>Gazebo/White</material>
<selfCollide>true</selfCollide>
</gazebo>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 1 0"/>
<limit effort="30" lower="-2.0" upper="2.0" velocity="2.0"/>
- <joint_properties damping="100.0" friction="1000.0" />
- <dynamics damping="1000"/>
+ <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
+ <dynamics damping="0.25" friction="${3.0/7}"/>
</joint>
- <transmission name="j2_transmission" type="pr2_mechanism_model/SimpleTransmission">
- <actuator name="j2"/>
- <joint name="wam_joint_2"/>
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
+ <transmission name="j2_transmission">
+ <type>transmission_interface/SimpleTransmission"</type>
+ <joint name="wam_joint_2">
+ <hardwareInterface>EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="j2">
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
</transmission>
</xacro:macro>
</link>
<gazebo reference="wam_link_3">
- <material>Gazebo/Grey</material>
+ <material>Gazebo/White</material>
<selfCollide>true</selfCollide>
</gazebo>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 0 1"/>
<limit effort="30" lower="-2.8" upper="2.8" velocity="2.0"/>
- <joint_properties damping="100.0" friction="1000.0" />
- <dynamics damping="1000"/>
+ <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
+ <dynamics damping="0.75" friction="${3.0/7}"/>
</joint>
- <transmission name="j3_transmission" type="pr2_mechanism_model/SimpleTransmission">
- <actuator name="j3"/>
- <joint name="wam_joint_3"/>
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
+ <transmission name="j3_transmission">
+ <type>transmission_interface/SimpleTransmission"</type>
+ <joint name="wam_joint_3">
+ <hardwareInterface>EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="j3">
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
</transmission>
</xacro:macro>
</link>
<gazebo reference="wam_link_4">
- <material>Gazebo/Grey</material>
+ <material>Gazebo/White</material>
<selfCollide>true</selfCollide>
</gazebo>
<origin rpy="-1.57079632679 0 0" xyz="0.045 0.0 0.55"/>
<axis xyz="0 0 1"/>
<limit effort="35" lower="-0.9" upper="3.1" velocity="2.0"/>
- <joint_properties damping="100.0" friction="1000.0" />
- <dynamics damping="1000"/>
+ <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
+ <dynamics damping="0.4" friction="${3.0/7}"/>
</joint>
- <transmission name="j4_transmission" type="pr2_mechanism_model/SimpleTransmission">
- <actuator name="j4"/>
- <joint name="wam_joint_4"/>
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
+ <transmission name="j4_transmission">
+ <type>transmission_interface/SimpleTransmission"</type>
+ <joint name="wam_joint_4">
+ <hardwareInterface>EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="j4">
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
</transmission>
</xacro:macro>
</link>
<gazebo reference="wam_link_5">
- <material>Gazebo/Grey</material>
+ <material>Gazebo/White</material>
<selfCollide>true</selfCollide>
</gazebo>
<origin rpy="1.57079632679 0 0" xyz="-0.045 -0.3 0.0"/>
<axis xyz="0 0 1"/>
<limit effort="30" lower="-4.8" upper="1.3" velocity="2.0"/>
- <joint_properties damping="100.0" friction="1000.0" />
- <dynamics damping="1000"/>
+ <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
+ <dynamics damping="0.25" friction="${3.0/7}"/>
</joint>
- <transmission name="j5_transmission" type="pr2_mechanism_model/SimpleTransmission">
- <actuator name="j5"/>
- <joint name="wam_joint_5"/>
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
+ <transmission name="j5_transmission">
+ <type>transmission_interface/SimpleTransmission"</type>
+ <joint name="wam_joint_5">
+ <hardwareInterface>EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="j5">
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
</transmission>
</xacro:macro>
</link>
<gazebo reference="wam_link_6">
- <material>Gazebo/Grey</material>
+ <material>Gazebo/White</material>
<selfCollide>true</selfCollide>
</gazebo>
<origin rpy="-1.57079632679 0 0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 0 1"/>
<limit effort="30" lower="-1.6" upper="1.6" velocity="2.0"/>
- <joint_properties damping="100.0" friction="1000.0" />
- <dynamics damping="1000"/>
+ <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
+ <dynamics damping="0.05" friction="0.0"/>
</joint>
- <transmission name="j6_transmission" type="pr2_mechanism_model/SimpleTransmission">
- <actuator name="j6"/>
- <joint name="wam_joint_6"/>
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
+ <transmission name="j6_transmission">
+ <type>transmission_interface/SimpleTransmission"</type>
+ <joint name="wam_joint_6">
+ <hardwareInterface>EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="j6">
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
</transmission>
</xacro:macro>
</link>
<gazebo reference="wam_link_7">
- <material>Gazebo/Grey</material>
+ <material>Gazebo/White</material>
<selfCollide>true</selfCollide>
</gazebo>
<origin rpy="1.57079632679 0 0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 0 1"/>
<limit effort="30" lower="-2.2" upper="2.2" velocity="2.0"/>
- <joint_properties damping="100.0" friction="1000.0" />
- <dynamics damping="1000"/>
+ <!-- <joint_properties damping="100.0" friction="1000.0" /> -->
+ <dynamics damping="0.05" friction="${3.0/7}"/>
</joint>
- <transmission name="j7_transmission" type="pr2_mechanism_model/SimpleTransmission">
- <actuator name="j7"/>
- <joint name="wam_joint_7"/>
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
+ <transmission name="j7_transmission">
+ <type>transmission_interface/SimpleTransmission"</type>
+ <joint name="wam_joint_7">
+ <hardwareInterface>EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="j7">
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
</transmission>
</xacro:macro>
<?xml version="1.0"?>
-<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
- xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
- xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
- xmlns:xacro="http://ros.org/wiki/xacro"
- name="wam">
+
+<robot name ="wam" xmlns:xacro="http://ros.org/wiki/xacro">
<property name="M_PI" value="3.1415926535897931" />
<link name="world" />
- <xacro:include filename="$(find gazebo_worlds)/objects/table.urdf.xacro" />
+ <xacro:include filename="$(find wam_description)/xacro/table.urdf.xacro" />
<joint name="world_table_joint" type="fixed" static="true">
<parent link="world"/>
</joint>
</robot>
-
</collision>
</link>
<gazebo reference="wam_tool_plate">
- <material>Gazebo/Grey</material>
+ <material>Gazebo/White</material>
<selfCollide>true</selfCollide>
</gazebo>
cmake_minimum_required(VERSION 2.8.3)
-project(wam_control_gazebo)
+project(wam_gazebo_ros_control)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
# find_package(Boost REQUIRED COMPONENTS system)
find_package(gazebo REQUIRED)
-
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
-# LIBRARIES wam_control_gazebo
+# LIBRARIES wam_gazebo_ros_control
# CATKIN_DEPENDS other_catkin_pkg
# DEPENDS system_lib
)
)
## Declare a cpp library
-add_library(wam_control_gazebo
- src/robot_sim_wam.cpp
+add_library(wam_gazebo_ros_control
+ src/wam_robot_hw_sim.cpp
)
## Declare a cpp executable
-# add_executable(wam_control_gazebo_node src/wam_control_gazebo_node.cpp)
+# add_executable(wam_gazebo_ros_control_node src/wam_gazebo_ros_control_node.cpp)
## Add cmake target dependencies of the executable/library
## as an example, message headers may need to be generated before nodes
-# add_dependencies(wam_control_gazebo_node wam_control_gazebo_generate_messages_cpp)
+# add_dependencies(wam_gazebo_ros_control_node wam_gazebo_ros_control_generate_messages_cpp)
## Specify libraries to link a library or executable target against
-# target_link_libraries(wam_control_gazebo_node
-# ${catkin_LIBRARIES}
-# )
+#target_link_libraries(${PROJECT_NAME}
+# ${catkin_LIBRARIES}
+#)
#############
## Install ##
# )
## Mark executables and/or libraries for installation
-# install(TARGETS wam_control_gazebo wam_control_gazebo_node
+install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+ LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
+ )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
-# install(FILES
+install(FILES robot_sim_plugins.xml
# # myfile1
# # myfile2
-# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
-# )
+ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
-# catkin_add_gtest(${PROJECT_NAME}-test test/test_wam_control_gazebo.cpp)
+# catkin_add_gtest(${PROJECT_NAME}-test test/test_wam_gazebo_ros_control.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
<?xml version="1.0"?>
<package>
- <name>wam_control_gazebo</name>
+ <name>wam_gazebo_ros_control</name>
<version>2.0.0</version>
- <description>The wam_control_gazebo package</description>
+ <description>The wam_gazebo_ros_control package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <test_depend>gtest</test_depend> -->
<buildtool_depend>catkin</buildtool_depend>
- <buildtool_depend>gazebo_ros_control</buildtool_depend>
- <buildtool_depend>gazebo_ros_control_plugin</buildtool_depend>
- <buildtool_depend>wam_description</buildtool_depend>
- <buildtool_depend>gazebo</buildtool_depend>
+ <build_depend>gazebo_ros_control</build_depend>
+ <!--build_depend>gazebo_ros_control_plugin</build_depend-->
+ <build_depend>wam_description</build_depend>
+ <build_depend>gazebo</build_depend>
+
+ <!--run_depend>roscpp</run_depend-->
+ <!--run_depend>gazebo</run_depend-->
+ <!--run_depend>gazebo_ros</run_depend-->
+ <!--run_depend>controller_manager</run_depend-->
+ <!--run_depend>pluginlib</run_depend-->
+ <!--run_depend>transmission_interface</run_depend-->
+ <!--run_depend>urdf</run_depend-->
+ <run_depend>gazebo_ros_control</run_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
- <gazebo_ros_control plugin="${prefix}/robot_sim_plugins.xml" />
+ <gazebo_ros_control plugin="${prefix}/wam_gazebo_ros_control_plugins.xml" />
</export>
-</package>
\ No newline at end of file
+</package>
#include <gazebo/physics/physics.hh>
#include <gazebo/common/common.hh>
-namespace wam_control_gazebo
+namespace wam_gazebo_ros_control
{
- class RobotSimWam:public gazebo_ros_control::RobotHWSim
+ class WamRobotHWSim:public gazebo_ros_control::RobotHWSim
{
unsigned int n_dof_;
public:
- RobotSimWam(void):n_dof_(7),joint_name_(n_dof_),joint_position_(n_dof_),
+ WamRobotHWSim(void):n_dof_(7),joint_name_(n_dof_),joint_position_(n_dof_),
joint_velocity_(n_dof_),joint_effort_(n_dof_),joint_effort_command_(n_dof_)
{
joint_name_[0]="wam_joint_1";
};
}
-PLUGINLIB_DECLARE_CLASS(wam_control_gazebo,RobotSimWam,wam_control_gazebo::RobotSimWam,
- gazebo_ros_control::RobotHWSim)
+PLUGINLIB_EXPORT_CLASS(wam_gazebo_ros_control::WamRobotHWSim,gazebo_ros_control::RobotHWSim)
-<library path="lib/libwam_control_gazebo">
+<library path="lib/libwam_gazebo_ros_control">
<class
- name="wam_control_gazebo/RobotSimWam"
- type="wam_control_gazebo::RobotSimWam"
+ name="wam_gazebo_ros_control/WamRobotHWSim"
+ type="wam_gazebo_ros_control::WamRobotHWSim"
base_class_type="gazebo_ros_control::RobotHWSim">
<description>
A ROS/Gazebo interface for Barrett WAM, exporting a