Skip to content

Commit 97dd175

Browse files
authored
Add tf_frame_prefix parameters to mecanum_drive_controller (#1680)
1 parent 3ed529d commit 97dd175

6 files changed

+273
-69
lines changed

mecanum_drive_controller/src/mecanum_drive_controller.cpp

Lines changed: 26 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -148,10 +148,31 @@ controller_interface::CallbackReturn MecanumDriveController::on_configure(
148148
return controller_interface::CallbackReturn::ERROR;
149149
}
150150

151+
// Append the tf prefix if there is one
152+
std::string tf_prefix = "";
153+
if (params_.tf_frame_prefix_enable)
154+
{
155+
tf_prefix = params_.tf_frame_prefix != "" ? params_.tf_frame_prefix
156+
: std::string(get_node()->get_namespace());
157+
158+
// Make sure prefix does not start with '/' and always ends with '/'
159+
if (tf_prefix.back() != '/')
160+
{
161+
tf_prefix = tf_prefix + "/";
162+
}
163+
if (tf_prefix.front() == '/')
164+
{
165+
tf_prefix.erase(0, 1);
166+
}
167+
}
168+
169+
const auto odom_frame_id = tf_prefix + params_.odom_frame_id;
170+
const auto base_frame_id = tf_prefix + params_.base_frame_id;
171+
151172
rt_odom_state_publisher_->lock();
152173
rt_odom_state_publisher_->msg_.header.stamp = get_node()->now();
153-
rt_odom_state_publisher_->msg_.header.frame_id = params_.odom_frame_id;
154-
rt_odom_state_publisher_->msg_.child_frame_id = params_.base_frame_id;
174+
rt_odom_state_publisher_->msg_.header.frame_id = odom_frame_id;
175+
rt_odom_state_publisher_->msg_.child_frame_id = base_frame_id;
155176
rt_odom_state_publisher_->msg_.pose.pose.position.z = 0;
156177

157178
auto & covariance = rt_odom_state_publisher_->msg_.twist.covariance;
@@ -182,8 +203,8 @@ controller_interface::CallbackReturn MecanumDriveController::on_configure(
182203
rt_tf_odom_state_publisher_->lock();
183204
rt_tf_odom_state_publisher_->msg_.transforms.resize(1);
184205
rt_tf_odom_state_publisher_->msg_.transforms[0].header.stamp = get_node()->now();
185-
rt_tf_odom_state_publisher_->msg_.transforms[0].header.frame_id = params_.odom_frame_id;
186-
rt_tf_odom_state_publisher_->msg_.transforms[0].child_frame_id = params_.base_frame_id;
206+
rt_tf_odom_state_publisher_->msg_.transforms[0].header.frame_id = odom_frame_id;
207+
rt_tf_odom_state_publisher_->msg_.transforms[0].child_frame_id = base_frame_id;
187208
rt_tf_odom_state_publisher_->msg_.transforms[0].transform.translation.z = 0.0;
188209
rt_tf_odom_state_publisher_->unlock();
189210

@@ -207,7 +228,7 @@ controller_interface::CallbackReturn MecanumDriveController::on_configure(
207228

208229
controller_state_publisher_->lock();
209230
controller_state_publisher_->msg_.header.stamp = get_node()->now();
210-
controller_state_publisher_->msg_.header.frame_id = params_.odom_frame_id;
231+
controller_state_publisher_->msg_.header.frame_id = odom_frame_id;
211232
controller_state_publisher_->unlock();
212233

213234
RCLCPP_INFO(get_node()->get_logger(), "MecanumDriveController configured successfully");

mecanum_drive_controller/src/mecanum_drive_controller.yaml

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -113,12 +113,21 @@ mecanum_drive_controller:
113113
read_only: false,
114114
}
115115

116+
tf_frame_prefix_enable: {
117+
type: bool,
118+
default_value: true,
119+
description: "Enables or disables appending ``tf_frame_prefix`` to tf frame id's. See its parameter description for more information.",
120+
}
121+
tf_frame_prefix: {
122+
type: string,
123+
default_value: "",
124+
description: "(optional) Prefix to be appended to the tf frames, will be added to odom_frame_id and base_frame_id before publishing. If the parameter is empty, controller's namespace will be used.",
125+
}
116126
base_frame_id: {
117127
type: string,
118128
default_value: "base_link",
119129
description: "Base frame_id set to value of base_frame_id.",
120130
read_only: false,
121-
122131
}
123132
odom_frame_id: {
124133
type: string,
Lines changed: 41 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -1,40 +1,41 @@
1-
test_mecanum_drive_controller:
2-
ros__parameters:
3-
reference_timeout: 0.9
4-
5-
front_left_wheel_command_joint_name: "front_left_wheel_joint"
6-
front_right_wheel_command_joint_name: "front_right_wheel_joint"
7-
rear_right_wheel_command_joint_name: "back_right_wheel_joint"
8-
rear_left_wheel_command_joint_name: "back_left_wheel_joint"
9-
10-
kinematics:
11-
base_frame_offset: { x: 0.0, y: 0.0, theta: 0.0 }
12-
wheels_radius: 0.5
13-
sum_of_robot_center_projection_on_X_Y_axis: 1.0
14-
15-
base_frame_id: "base_link"
16-
odom_frame_id: "odom"
17-
enable_odom_tf: true
18-
twist_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
19-
pose_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
20-
21-
22-
test_mecanum_drive_controller_with_rotation:
23-
ros__parameters:
24-
reference_timeout: 5.0
25-
26-
front_left_wheel_command_joint_name: "front_left_wheel_joint"
27-
front_right_wheel_command_joint_name: "front_right_wheel_joint"
28-
rear_right_wheel_command_joint_name: "rear_right_wheel_joint"
29-
rear_left_wheel_command_joint_name: "rear_left_wheel_joint"
30-
31-
kinematics:
32-
base_frame_offset: { x: 1.0, y: 2.0, theta: 3.0 }
33-
wheels_radius: 0.05
34-
sum_of_robot_center_projection_on_X_Y_axis: 0.2925
35-
36-
base_frame_id: "base_link"
37-
odom_frame_id: "odom"
38-
enable_odom_tf: true
39-
pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001]
40-
twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001]
1+
/**:
2+
test_mecanum_drive_controller:
3+
ros__parameters:
4+
reference_timeout: 0.9
5+
6+
front_left_wheel_command_joint_name: "front_left_wheel_joint"
7+
front_right_wheel_command_joint_name: "front_right_wheel_joint"
8+
rear_right_wheel_command_joint_name: "back_right_wheel_joint"
9+
rear_left_wheel_command_joint_name: "back_left_wheel_joint"
10+
11+
kinematics:
12+
base_frame_offset: { x: 0.0, y: 0.0, theta: 0.0 }
13+
wheels_radius: 0.5
14+
sum_of_robot_center_projection_on_X_Y_axis: 1.0
15+
16+
base_frame_id: "base_link"
17+
odom_frame_id: "odom"
18+
enable_odom_tf: true
19+
twist_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
20+
pose_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
21+
22+
23+
test_mecanum_drive_controller_with_rotation:
24+
ros__parameters:
25+
reference_timeout: 5.0
26+
27+
front_left_wheel_command_joint_name: "front_left_wheel_joint"
28+
front_right_wheel_command_joint_name: "front_right_wheel_joint"
29+
rear_right_wheel_command_joint_name: "rear_right_wheel_joint"
30+
rear_left_wheel_command_joint_name: "rear_left_wheel_joint"
31+
32+
kinematics:
33+
base_frame_offset: { x: 1.0, y: 2.0, theta: 3.0 }
34+
wheels_radius: 0.05
35+
sum_of_robot_center_projection_on_X_Y_axis: 0.2925
36+
37+
base_frame_id: "base_link"
38+
odom_frame_id: "odom"
39+
enable_odom_tf: true
40+
pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001]
41+
twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001]
Lines changed: 21 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -1,24 +1,25 @@
1-
test_mecanum_drive_controller:
2-
ros__parameters:
3-
reference_timeout: 0.1
1+
/**:
2+
test_mecanum_drive_controller:
3+
ros__parameters:
4+
reference_timeout: 0.1
45

5-
front_left_wheel_command_joint_name: "front_left_wheel_joint"
6-
front_right_wheel_command_joint_name: "front_right_wheel_joint"
7-
rear_right_wheel_command_joint_name: "back_right_wheel_joint"
8-
rear_left_wheel_command_joint_name: "back_left_wheel_joint"
6+
front_left_wheel_command_joint_name: "front_left_wheel_joint"
7+
front_right_wheel_command_joint_name: "front_right_wheel_joint"
8+
rear_right_wheel_command_joint_name: "back_right_wheel_joint"
9+
rear_left_wheel_command_joint_name: "back_left_wheel_joint"
910

10-
front_left_wheel_state_joint_name: "state_front_left_wheel_joint"
11-
front_right_wheel_state_joint_name: "state_front_right_wheel_joint"
12-
rear_right_wheel_state_joint_name: "state_back_right_wheel_joint"
13-
rear_left_wheel_state_joint_name: "state_back_left_wheel_joint"
11+
front_left_wheel_state_joint_name: "state_front_left_wheel_joint"
12+
front_right_wheel_state_joint_name: "state_front_right_wheel_joint"
13+
rear_right_wheel_state_joint_name: "state_back_right_wheel_joint"
14+
rear_left_wheel_state_joint_name: "state_back_left_wheel_joint"
1415

15-
kinematics:
16-
base_frame_offset: { x: 0.0, y: 0.0, theta: 0.0 }
17-
wheels_radius: 0.5
18-
sum_of_robot_center_projection_on_X_Y_axis: 1.0
16+
kinematics:
17+
base_frame_offset: { x: 0.0, y: 0.0, theta: 0.0 }
18+
wheels_radius: 0.5
19+
sum_of_robot_center_projection_on_X_Y_axis: 1.0
1920

20-
base_frame_id: "base_link"
21-
odom_frame_id: "odom"
22-
enable_odom_tf: true
23-
twist_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
24-
pose_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
21+
base_frame_id: "base_link"
22+
odom_frame_id: "odom"
23+
enable_odom_tf: true
24+
twist_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
25+
pose_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]

mecanum_drive_controller/test/test_mecanum_drive_controller.cpp

Lines changed: 160 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -118,6 +118,166 @@ TEST_F(MecanumDriveControllerTest, when_controller_configured_expect_properly_ex
118118
}
119119
}
120120

121+
TEST_F(MecanumDriveControllerTest, configure_succeeds_tf_test_prefix_false_no_namespace)
122+
{
123+
std::string odom_id = "odom";
124+
std::string base_link_id = "base_link";
125+
std::string frame_prefix = "test_prefix";
126+
127+
auto node_options = controller_->define_custom_node_options();
128+
node_options.append_parameter_override("tf_frame_prefix_enable", rclcpp::ParameterValue(false));
129+
node_options.append_parameter_override("tf_frame_prefix", rclcpp::ParameterValue(frame_prefix));
130+
node_options.append_parameter_override("odom_frame_id", rclcpp::ParameterValue(odom_id));
131+
node_options.append_parameter_override("base_frame_id", rclcpp::ParameterValue(base_link_id));
132+
133+
SetUpController("test_mecanum_drive_controller", node_options);
134+
135+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
136+
137+
auto odometry_message = controller_->get_rt_odom_state_publisher_msg();
138+
std::string test_odom_frame_id = odometry_message.header.frame_id;
139+
std::string test_base_frame_id = odometry_message.child_frame_id;
140+
/* tf_frame_prefix_enable is false so no modifications to the frame id's */
141+
ASSERT_EQ(test_odom_frame_id, odom_id);
142+
ASSERT_EQ(test_base_frame_id, base_link_id);
143+
}
144+
145+
TEST_F(MecanumDriveControllerTest, configure_succeeds_tf_test_prefix_true_no_namespace)
146+
{
147+
std::string odom_id = "odom";
148+
std::string base_link_id = "base_link";
149+
std::string frame_prefix = "test_prefix";
150+
151+
auto node_options = controller_->define_custom_node_options();
152+
node_options.append_parameter_override("tf_frame_prefix_enable", rclcpp::ParameterValue(true));
153+
node_options.append_parameter_override("tf_frame_prefix", rclcpp::ParameterValue(frame_prefix));
154+
node_options.append_parameter_override("odom_frame_id", rclcpp::ParameterValue(odom_id));
155+
node_options.append_parameter_override("base_frame_id", rclcpp::ParameterValue(base_link_id));
156+
157+
SetUpController("test_mecanum_drive_controller", node_options);
158+
159+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
160+
161+
auto odometry_message = controller_->get_rt_odom_state_publisher_msg();
162+
std::string test_odom_frame_id = odometry_message.header.frame_id;
163+
std::string test_base_frame_id = odometry_message.child_frame_id;
164+
165+
/* tf_frame_prefix_enable is true and frame_prefix is not blank so should be appended to the
166+
frame
167+
* id's */
168+
ASSERT_EQ(test_odom_frame_id, frame_prefix + "/" + odom_id);
169+
ASSERT_EQ(test_base_frame_id, frame_prefix + "/" + base_link_id);
170+
}
171+
172+
TEST_F(MecanumDriveControllerTest, configure_succeeds_tf_blank_prefix_true_no_namespace)
173+
{
174+
std::string odom_id = "odom";
175+
std::string base_link_id = "base_link";
176+
std::string frame_prefix = "";
177+
178+
auto node_options = controller_->define_custom_node_options();
179+
node_options.append_parameter_override("tf_frame_prefix_enable", rclcpp::ParameterValue(true));
180+
node_options.append_parameter_override("tf_frame_prefix", rclcpp::ParameterValue(frame_prefix));
181+
node_options.append_parameter_override("odom_frame_id", rclcpp::ParameterValue(odom_id));
182+
node_options.append_parameter_override("base_frame_id", rclcpp::ParameterValue(base_link_id));
183+
184+
SetUpController("test_mecanum_drive_controller", node_options);
185+
186+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
187+
188+
auto odometry_message = controller_->get_rt_odom_state_publisher_msg();
189+
std::string test_odom_frame_id = odometry_message.header.frame_id;
190+
std::string test_base_frame_id = odometry_message.child_frame_id;
191+
/* tf_frame_prefix_enable is true but frame_prefix is blank so should not be appended to the
192+
frame
193+
* id's */
194+
ASSERT_EQ(test_odom_frame_id, odom_id);
195+
ASSERT_EQ(test_base_frame_id, base_link_id);
196+
}
197+
198+
TEST_F(MecanumDriveControllerTest, configure_succeeds_tf_test_prefix_false_set_namespace)
199+
{
200+
std::string test_namespace = "/test_namespace";
201+
202+
std::string odom_id = "odom";
203+
std::string base_link_id = "base_link";
204+
std::string frame_prefix = "test_prefix";
205+
206+
auto node_options = controller_->define_custom_node_options();
207+
node_options.append_parameter_override("tf_frame_prefix_enable", rclcpp::ParameterValue(false));
208+
node_options.append_parameter_override("tf_frame_prefix", rclcpp::ParameterValue(frame_prefix));
209+
node_options.append_parameter_override("odom_frame_id", rclcpp::ParameterValue(odom_id));
210+
node_options.append_parameter_override("base_frame_id", rclcpp::ParameterValue(base_link_id));
211+
212+
SetUpController("test_mecanum_drive_controller", node_options, test_namespace);
213+
214+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
215+
216+
auto odometry_message = controller_->get_rt_odom_state_publisher_msg();
217+
std::string test_odom_frame_id = odometry_message.header.frame_id;
218+
std::string test_base_frame_id = odometry_message.child_frame_id;
219+
/* tf_frame_prefix_enable is false so no modifications to the frame id's */
220+
ASSERT_EQ(test_odom_frame_id, odom_id);
221+
ASSERT_EQ(test_base_frame_id, base_link_id);
222+
}
223+
224+
TEST_F(MecanumDriveControllerTest, configure_succeeds_tf_test_prefix_true_set_namespace)
225+
{
226+
std::string test_namespace = "/test_namespace";
227+
228+
std::string odom_id = "odom";
229+
std::string base_link_id = "base_link";
230+
std::string frame_prefix = "test_prefix";
231+
232+
auto node_options = controller_->define_custom_node_options();
233+
node_options.append_parameter_override("tf_frame_prefix_enable", rclcpp::ParameterValue(true));
234+
node_options.append_parameter_override("tf_frame_prefix", rclcpp::ParameterValue(frame_prefix));
235+
node_options.append_parameter_override("odom_frame_id", rclcpp::ParameterValue(odom_id));
236+
node_options.append_parameter_override("base_frame_id", rclcpp::ParameterValue(base_link_id));
237+
238+
SetUpController("test_mecanum_drive_controller", node_options, test_namespace);
239+
240+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
241+
242+
auto odometry_message = controller_->get_rt_odom_state_publisher_msg();
243+
std::string test_odom_frame_id = odometry_message.header.frame_id;
244+
std::string test_base_frame_id = odometry_message.child_frame_id;
245+
246+
/* tf_frame_prefix_enable is true and frame_prefix is not blank so should be appended to the
247+
frame
248+
* id's instead of the namespace*/
249+
ASSERT_EQ(test_odom_frame_id, frame_prefix + "/" + odom_id);
250+
ASSERT_EQ(test_base_frame_id, frame_prefix + "/" + base_link_id);
251+
}
252+
253+
TEST_F(MecanumDriveControllerTest, configure_succeeds_tf_blank_prefix_true_set_namespace)
254+
{
255+
std::string test_namespace = "/test_namespace";
256+
std::string odom_id = "odom";
257+
std::string base_link_id = "base_link";
258+
std::string frame_prefix = "";
259+
260+
auto node_options = controller_->define_custom_node_options();
261+
node_options.append_parameter_override("tf_frame_prefix_enable", rclcpp::ParameterValue(true));
262+
node_options.append_parameter_override("tf_frame_prefix", rclcpp::ParameterValue(frame_prefix));
263+
node_options.append_parameter_override("odom_frame_id", rclcpp::ParameterValue(odom_id));
264+
node_options.append_parameter_override("base_frame_id", rclcpp::ParameterValue(base_link_id));
265+
266+
SetUpController("test_mecanum_drive_controller", node_options, test_namespace);
267+
268+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
269+
270+
auto odometry_message = controller_->get_rt_odom_state_publisher_msg();
271+
std::string test_odom_frame_id = odometry_message.header.frame_id;
272+
std::string test_base_frame_id = odometry_message.child_frame_id;
273+
std::string ns_prefix = test_namespace.erase(0, 1) + "/";
274+
/* tf_frame_prefix_enable is true but frame_prefix is blank so namespace should be appended to
275+
the
276+
* frame id's */
277+
ASSERT_EQ(test_odom_frame_id, ns_prefix + odom_id);
278+
ASSERT_EQ(test_base_frame_id, ns_prefix + base_link_id);
279+
}
280+
121281
TEST_F(MecanumDriveControllerTest, when_controller_is_activated_expect_reference_reset)
122282
{
123283
SetUpController();

0 commit comments

Comments
 (0)