scout joint controller setup

This commit is contained in:
Ruixiang Du
2020-03-25 00:03:18 +08:00
parent 5279161dbf
commit 9c26ce9c34
8 changed files with 57 additions and 102 deletions

View File

@@ -10,7 +10,7 @@
</plugin>
</gazebo>
<gazebo>
<!-- <gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<updateRate>100.0</updateRate>
<robotNamespace></robotNamespace>
@@ -22,16 +22,15 @@
<wheelDiameter>0.32918</wheelDiameter>
<robotBaseFrame>base_link</robotBaseFrame>
<torque>1000</torque>
<!-- <topicName>cmd_vel</topicName> -->
<commandTopic>cmd_vel</commandTopic>
<broadcastTF>1</broadcastTF>
<broadcastTF>true</broadcastTF>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<covariance_x>0.000100</covariance_x>
<covariance_y>0.000100</covariance_y>
<covariance_yaw>0.010000</covariance_yaw>
</plugin>
</gazebo>
</gazebo> -->
<!-- <gazebo>
<plugin name="object_controller" filename="libgazebo_ros_planar_move.so">
@@ -41,5 +40,5 @@
<odometryRate>20.0</odometryRate>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo> -->
</gazebo> -->
</robot>

View File

@@ -89,7 +89,7 @@
<!-- For testing, hang the robot up in the air -->
<!-- <link name="world" />
<joint name="world_to_base_link=" type="fixed">
<origin xyz="0 0 1.0" rpy="0 0 0" />
<origin xyz="0 0 0.5" rpy="0 0 0" />
<parent link="world"/>
<child link="base_link"/>
</joint> -->

View File

@@ -55,16 +55,6 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<axis xyz="0 -1 0" rpy="0 0 0" />
</joint>
<!-- <transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${wheel_prefix}_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="${wheel_prefix}_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission> -->
<!-- Gazebo definitions -->
<gazebo reference="${wheel_prefix}_wheel_link">
<mu1 value="1.0"/>
@@ -73,6 +63,15 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<kd value="1.0" />
<fdir1 value="1 0 0"/>
</gazebo>
<transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${wheel_prefix}_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="${wheel_prefix}_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
</xacro:macro>
</robot>

View File

@@ -55,16 +55,6 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<axis xyz="0 -1 0" rpy="0 0 0" />
</joint>
<!-- <transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${wheel_prefix}_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="${wheel_prefix}_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission> -->
<!-- Gazebo definitions -->
<gazebo reference="${wheel_prefix}_wheel_link">
<mu1 value="1.0"/>
@@ -73,6 +63,16 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<kd value="1.0" />
<fdir1 value="1 0 0"/>
</gazebo>
<transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${wheel_prefix}_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="${wheel_prefix}_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
</xacro:macro>
</robot>