@@ -90,9 +90,12 @@ TwistServerNode::TwistServerNode()
90
90
get_node_topics_interface(), get_node_services_interface()))
91
91
{
92
92
getParameters ();
93
- if (use_stamped_msgs) {
93
+ if (use_stamped_msgs)
94
+ {
94
95
vel_stamped_pub = create_publisher<geometry_msgs::msg::TwistStamped>(" cmd_vel" , 1 );
95
- } else {
96
+ }
97
+ else
98
+ {
96
99
vel_pub = create_publisher<geometry_msgs::msg::Twist>(" cmd_vel" , 1 );
97
100
}
98
101
createInteractiveMarkers ();
@@ -105,29 +108,41 @@ void TwistServerNode::getParameters()
105
108
rclcpp::Parameter robot_name_param;
106
109
rclcpp::Parameter use_stamped_msgs_param;
107
110
108
- if (this ->get_parameter (" link_name" , link_name_param)) {
111
+ if (this ->get_parameter (" link_name" , link_name_param))
112
+ {
109
113
link_name = link_name_param.as_string ();
110
- } else {
114
+ }
115
+ else
116
+ {
111
117
link_name = " base_link" ;
112
118
}
113
119
114
- if (this ->get_parameter (" robot_name" , robot_name_param)) {
120
+ if (this ->get_parameter (" robot_name" , robot_name_param))
121
+ {
115
122
robot_name = robot_name_param.as_string ();
116
- } else {
123
+ }
124
+ else
125
+ {
117
126
robot_name = " robot" ;
118
127
}
119
128
120
- if (this ->get_parameter (" use_stamped_msgs" , use_stamped_msgs_param)) {
129
+ if (this ->get_parameter (" use_stamped_msgs" , use_stamped_msgs_param))
130
+ {
121
131
use_stamped_msgs = use_stamped_msgs_param.as_bool ();
122
- } else {
132
+ }
133
+ else
134
+ {
123
135
use_stamped_msgs = false ;
124
136
}
125
137
126
138
// Ensure parameters are loaded correctly, otherwise, manually set values for linear config
127
- if (this ->get_parameters (" linear_scale" , linear_drive_scale_map)) {
139
+ if (this ->get_parameters (" linear_scale" , linear_drive_scale_map))
140
+ {
128
141
this ->get_parameters (" max_positive_linear_velocity" , max_positive_linear_velocity_map);
129
142
this ->get_parameters (" max_negative_linear_velocity" , max_negative_linear_velocity_map);
130
- } else {
143
+ }
144
+ else
145
+ {
131
146
linear_drive_scale_map[" x" ] = 1.0 ;
132
147
max_positive_linear_velocity_map[" x" ] = 1.0 ;
133
148
max_negative_linear_velocity_map[" x" ] = -1.0 ;
@@ -150,7 +165,8 @@ void TwistServerNode::createInteractiveMarkers()
150
165
151
166
control.orientation_mode = visualization_msgs::msg::InteractiveMarkerControl::FIXED;
152
167
153
- if (linear_drive_scale_map.find (" x" ) != linear_drive_scale_map.end ()) {
168
+ if (linear_drive_scale_map.find (" x" ) != linear_drive_scale_map.end ())
169
+ {
154
170
control.orientation .w = 1 ;
155
171
control.orientation .x = 1 ;
156
172
control.orientation .y = 0 ;
@@ -160,7 +176,8 @@ void TwistServerNode::createInteractiveMarkers()
160
176
interactive_marker.controls .push_back (control);
161
177
}
162
178
163
- if (linear_drive_scale_map.find (" y" ) != linear_drive_scale_map.end ()) {
179
+ if (linear_drive_scale_map.find (" y" ) != linear_drive_scale_map.end ())
180
+ {
164
181
control.orientation .w = 1 ;
165
182
control.orientation .x = 0 ;
166
183
control.orientation .y = 0 ;
@@ -170,7 +187,8 @@ void TwistServerNode::createInteractiveMarkers()
170
187
interactive_marker.controls .push_back (control);
171
188
}
172
189
173
- if (linear_drive_scale_map.find (" z" ) != linear_drive_scale_map.end ()) {
190
+ if (linear_drive_scale_map.find (" z" ) != linear_drive_scale_map.end ())
191
+ {
174
192
control.orientation .w = 1 ;
175
193
control.orientation .x = 0 ;
176
194
control.orientation .y = 1 ;
@@ -208,27 +226,33 @@ void TwistServerNode::processFeedback(
208
226
vel_msg.angular .z = std::min (vel_msg.angular .z , max_angular_velocity);
209
227
vel_msg.angular .z = std::max (vel_msg.angular .z , -max_angular_velocity);
210
228
211
- if (linear_drive_scale_map.find (" x" ) != linear_drive_scale_map.end ()) {
229
+ if (linear_drive_scale_map.find (" x" ) != linear_drive_scale_map.end ()
230
+ {
212
231
vel_msg.linear .x = linear_drive_scale_map[" x" ] * feedback->pose .position .x ;
213
232
vel_msg.linear .x = std::min (vel_msg.linear .x , max_positive_linear_velocity_map[" x" ]);
214
233
vel_msg.linear .x = std::max (vel_msg.linear .x , max_negative_linear_velocity_map[" x" ]);
215
234
}
216
235
217
- if (linear_drive_scale_map.find (" y" ) != linear_drive_scale_map.end ()) {
236
+ if (linear_drive_scale_map.find (" y" ) != linear_drive_scale_map.end ())
237
+ {
218
238
vel_msg.linear .y = linear_drive_scale_map[" y" ] * feedback->pose .position .y ;
219
239
vel_msg.linear .y = std::min (vel_msg.linear .y , max_positive_linear_velocity_map[" y" ]);
220
240
vel_msg.linear .y = std::max (vel_msg.linear .y , max_negative_linear_velocity_map[" y" ]);
221
241
}
222
242
223
- if (linear_drive_scale_map.find (" z" ) != linear_drive_scale_map.end ()) {
243
+ if (linear_drive_scale_map.find (" z" ) != linear_drive_scale_map.end ())
244
+ {
224
245
vel_msg.linear .z = linear_drive_scale_map[" z" ] * feedback->pose .position .z ;
225
246
vel_msg.linear .z = std::min (vel_msg.linear .z , max_positive_linear_velocity_map[" z" ]);
226
247
vel_msg.linear .z = std::max (vel_msg.linear .z , max_negative_linear_velocity_map[" z" ]);
227
248
}
228
249
229
- if (use_stamped_msgs) {
250
+ if (use_stamped_msgs)
251
+ {
230
252
stampAndPublish (vel_msg);
231
- } else {
253
+ }
254
+ else
255
+ {
232
256
vel_pub->publish (vel_msg);
233
257
}
234
258
@@ -237,7 +261,8 @@ void TwistServerNode::processFeedback(
237
261
server->applyChanges ();
238
262
}
239
263
240
- void TwistServerNode::stampAndPublish (geometry_msgs::msg::Twist &msg) {
264
+ void TwistServerNode::stampAndPublish (geometry_msgs::msg::Twist &msg)
265
+ {
241
266
geometry_msgs::msg::TwistStamped stamped_msg;
242
267
243
268
stamped_msg.twist = msg;
0 commit comments