-
Notifications
You must be signed in to change notification settings - Fork 50
/
Copy pathsummit_xl_base.gazebo.xacro
90 lines (81 loc) · 3.49 KB
/
summit_xl_base.gazebo.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!-- ros control plugin -->
<xacro:macro name="ros_control">
<gazebo>
<plugin name="ros_control" filename="libgazebo_ros_control.so">
<robotParam>robot_description</robotParam>
<controlPeriod>0.001</controlPeriod>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
</xacro:macro>
<!-- skid steering plugin -->
<xacro:macro name="skid_steering" params="prefix publish_tf">
<gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<!--<robotNamespace>/summit_xl</robotNamespace>-->
<updateRate>50.0</updateRate>
<leftFrontJoint>${prefix}front_left_wheel_joint</leftFrontJoint>
<rightFrontJoint>${prefix}front_right_wheel_joint</rightFrontJoint>
<leftRearJoint>${prefix}back_left_wheel_joint</leftRearJoint>
<rightRearJoint>${prefix}back_right_wheel_joint</rightRearJoint>
<!-- wheelSeparation>0.566</wheelSeparation --> <!-- real parameter value -->
<wheelSeparation>0.462</wheelSeparation> <!-- works a bit better in Gazebo -->
<wheelDiameter>0.22</wheelDiameter>
<robotBaseFrame>${prefix}base_footprint</robotBaseFrame>
<torque>50</torque>
<commandTopic>robotnik_base_control/cmd_vel</commandTopic>
<odometryTopic>robotnik_base_control/odom</odometryTopic>
<odometryFrame>${prefix}odom</odometryFrame>
<broadcastTF>${publish_tf}</broadcastTF>
</plugin>
</gazebo>
</xacro:macro>
<xacro:macro name="omni_steering" params="prefix publish_tf">
<gazebo>
<plugin name="omni_steering" filename="libgazebo_ros_planar_move.so">
<commandTopic>robotnik_base_control/cmd_vel</commandTopic>
<odometryTopic>robotnik_base_control/odom</odometryTopic>
<odometryFrame>${prefix}odom</odometryFrame>
<odometryRate>50.0</odometryRate>
<robotBaseFrame>${prefix}base_footprint</robotBaseFrame>
<publishTF>${publish_tf}</publishTF>
<enableYAxis>true</enableYAxis>
</plugin>
</gazebo>
</xacro:macro>
<xacro:macro name="skid_steering" params="prefix publish_tf">
<gazebo>
<plugin name="skid_steering" filename="libgazebo_ros_planar_move.so">
<commandTopic>robotnik_base_control/cmd_vel</commandTopic>
<odometryTopic>robotnik_base_control/odom</odometryTopic>
<odometryFrame>${prefix}odom</odometryFrame>
<odometryRate>50.0</odometryRate>
<robotBaseFrame>${prefix}base_footprint</robotBaseFrame>
<publishTF>${publish_tf}</publishTF>
<enableYAxis>false</enableYAxis>
</plugin>
</gazebo>
</xacro:macro>
<xacro:macro name="ros_force_based_move" params="publish_tf prefix">
<gazebo>
<plugin name="ros_force_based_move" filename="librobotnik_force_based_move.so">
<commandTopic>robotnik_base_control/cmd_vel</commandTopic>
<odometryTopic>robotnik_base_control/odom</odometryTopic>
<odometryFrame>${prefix}odom</odometryFrame>
<yaw_velocity_p_gain>10000.0</yaw_velocity_p_gain>
<x_velocity_p_gain>10000.0</x_velocity_p_gain>
<y_velocity_p_gain>10000.0</y_velocity_p_gain>
<robotBaseFrame>${prefix}base_footprint</robotBaseFrame>
<commandWatchdog>1</commandWatchdog>
<odometryRate>50.0</odometryRate>
<publishOdometryTf>${publish_tf}</publishOdometryTf>
</plugin>
</gazebo>
</xacro:macro>
<gazebo reference="base_footprint">
<material>Gazebo/Green</material>
</gazebo>
</robot>