Implement basic pen position logger
This commit is contained in:
@@ -52,9 +52,9 @@
|
||||
|
||||
<joint name="eef_joint" type="fixed">
|
||||
<parent link="link_eef"/>
|
||||
<child link="test_link"/>
|
||||
<child link="pen_link"/>
|
||||
</joint>
|
||||
<link name="test_link">
|
||||
<link name="pen_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
@@ -72,6 +72,24 @@
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<!-- https://github.com/ros-simulation/gazebo_ros_pkgs/blob/foxy/gazebo_plugins/src/gazebo_ros_p3d.cpp -->
|
||||
<gazebo>
|
||||
<plugin name="pen_position" filename="libgazebo_ros_p3d.so">
|
||||
<!-- <alwaysOn>true</alwaysOn> -->
|
||||
<ros>
|
||||
<remapping>odom:=pen_position</remapping>
|
||||
</ros>
|
||||
<frame_name>world</frame_name>
|
||||
<!-- <body_name>pen_link</body_name> -->
|
||||
<body_name>link6</body_name>
|
||||
<!-- topic name is always /odom -->
|
||||
<!-- <topic_name>pen_position</topic_name> -->
|
||||
<update_rate>0.1</update_rate>
|
||||
<!-- <xyzOffsets>0 0 0</xyzOffsets> -->
|
||||
<!-- <rpyOffsets>0 0 0</rpyOffsets> -->
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
||||
<!-- <robot name="lite6_robot" xmlns:xacro="http://www.ros.org/wiki/xacro" xmlns:xi="http://www.w3.org/2001/XInclude">
|
||||
<xacro:include filename="$(find xarm_description)/urdf/lite6/lite6.urdf.xacro"/>
|
||||
|
||||
Reference in New Issue
Block a user