Skip to content

Commit 4289fd9

Browse files
author
Emiliano Borghi
committed
Set wheel odometry rate to 30 Hz
1 parent 6b8cfd3 commit 4289fd9

File tree

6 files changed

+19
-29
lines changed

6 files changed

+19
-29
lines changed

ca_description/urdf/create_base_gazebo.xacro

Lines changed: 3 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -2,22 +2,18 @@
22
<robot xmlns:xacro="http://ros.org/wiki/xacro">
33
<xacro:macro name="sim_create_base">
44

5-
<xacro:property name="diffdrive_update_rate" value="40"/>
6-
<xacro:property name="wheel_torque" value="0.5"/>
7-
<xacro:property name="wheel_accel" value="0.5"/>
8-
95
<gazebo>
106
<!-- Diff-drive controller -->
117
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
128
<alwaysOn>true</alwaysOn>
139
<rosDebugLevel>na</rosDebugLevel>
14-
<updateRate>${diffdrive_update_rate}</updateRate>
10+
<updateRate>30</updateRate>
1511
<leftJoint>wheel_left_joint</leftJoint>
1612
<rightJoint>wheel_right_joint</rightJoint>
1713
<wheelSeparation>${wheel_separation}</wheelSeparation>
1814
<wheelDiameter>${wheel_radius * 2}</wheelDiameter>
19-
<wheelTorque>${wheel_torque}</wheelTorque>
20-
<wheelAcceleration>${wheel_accel}</wheelAcceleration>
15+
<wheelTorque>0.5</wheelTorque>
16+
<wheelAcceleration>0.5</wheelAcceleration>
2117
<commandTopic>cmd_vel</commandTopic>
2218
<odometryTopic>odom</odometryTopic>
2319
<odometryFrame>odom</odometryFrame>

ca_driver/config/default.yaml

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,11 @@
1+
# Robot model
2+
robot_model: "CREATE_2"
3+
14
# The device path for the robot
25
dev: "/dev/ttyUSB0"
36

47
# Baud rate. Passing this parameter overwrites the inferred value based on the robot_model
5-
# baud: 115200
8+
baud: 115200
69

710
# Base frame ID
811
base_frame: "base_footprint"
@@ -14,7 +17,7 @@ odom_frame: "odom"
1417
latch_cmd_duration: 0.2
1518

1619
# Internal loop update rate (Hz)
17-
loop_hz: 10.0
20+
loop_hz: 30.0
1821

1922
# Whether to publish the transform between odom_frame and base_frame
2023
publish_tf: true

ca_driver/launch/create_2.launch

Lines changed: 3 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -4,19 +4,13 @@
44
<arg name="ns" value="create$(arg robot_id)" doc="Namespace of the robot. By default: create1"/>
55
<arg name="tf_prefix" value="$(arg ns)_tf" doc="Tf prefix"/>
66

7-
<arg name="config" default="$(find ca_driver)/config/default.yaml"
8-
doc="Absolute path to a configuration file (YAML)"/>
9-
107
<node name="ca_driver" pkg="ca_driver" type="ca_driver" output="screen">
11-
<rosparam command="load" file="$(arg config)" />
12-
13-
<param name="namespace" value="$(arg ns)"/>
14-
<param name="robot_model" value="CREATE_2" />
15-
<param name="tf_prefix" value="$(arg tf_prefix)"/>
8+
<rosparam command="load" file="$(find ca_driver)/config/default.yaml"/>
9+
<param name="namespace" value="$(arg ns)"/>
1610
</node>
1711

1812
<!-- Robot description -->
1913
<include ns="$(arg ns)" file="$(find ca_description)/launch/create_description.launch">
20-
<arg name="robot_id" value="$(arg robot_id)"/>
14+
<arg name="robot_id" value="$(arg robot_id)"/>
2115
</include>
2216
</launch>

ca_driver/src/create_driver.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,9 +52,10 @@ CreateDriver::CreateDriver(ros::NodeHandle& nh, ros::NodeHandle& ph)
5252
priv_nh_.param<std::string>("robot_model", robot_model_name, "CREATE_2");
5353
priv_nh_.param<double>("latch_cmd_duration", latch_duration_, 0.2);
5454
priv_nh_.param<bool>("publish_tf", publish_tf_, true);
55-
priv_nh_.param<std::string>("tf_prefix", tf_prefix_, "create_tf");
5655
priv_nh_.param<std::string>("namespace", topic_ns, "create");
5756

57+
nh_.param<std::string>("tf_prefix", tf_prefix_, "create_tf");
58+
5859
if (robot_model_name == "ROOMBA_400")
5960
{
6061
model_ = create::RobotModel::ROOMBA_400;

ca_gazebo/test/params/hz.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -48,13 +48,13 @@ imu_data:
4848

4949
joint_states:
5050
topic: "/create1/joint_states"
51-
hz: 40.0
51+
hz: 30.0
5252
hzerror: 1.0
5353
test_duration: 5.0
5454

5555
odom:
5656
topic: "/create1/odom"
57-
hz: 40.0
57+
hz: 30.0
5858
hzerror: 1.0
5959
test_duration: 5.0
6060

ca_node/launch/create_2.launch

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -4,19 +4,15 @@
44
<arg name="ns" value="create$(arg robot_id)" doc="Namespace of the robot. By default: create1"/>
55
<arg name="tf_prefix" value="$(arg ns)_tf" doc="Tf prefix"/>
66

7-
<arg name="config" default="$(find ca_driver)/config/default.yaml"
8-
doc="Absolute path to a configuration file (YAML)"/>
7+
<param name="tf_prefix" value="$(arg tf_prefix)"/>
98

109
<node name="ca_driver" pkg="ca_driver" type="ca_driver" output="screen" required="true">
11-
<rosparam command="load" file="$(arg config)" />
12-
13-
<param name="namespace" value="$(arg ns)"/>
14-
<param name="robot_model" value="CREATE_2" />
15-
<param name="tf_prefix" value="$(arg tf_prefix)"/>
10+
<rosparam command="load" file="$(find ca_driver)/config/default.yaml"/>
11+
<param name="namespace" value="$(arg ns)"/>
1612
</node>
1713

1814
<!-- Robot description -->
1915
<include ns="$(arg ns)" file="$(find ca_description)/launch/create_description.launch">
20-
<arg name="robot_id" value="$(arg robot_id)"/>
16+
<arg name="robot_id" value="$(arg robot_id)"/>
2117
</include>
2218
</launch>

0 commit comments

Comments
 (0)