Skip to content

Commit 0cd1f1a

Browse files
committed
More fixes.
1 parent 102bf69 commit 0cd1f1a

File tree

2 files changed

+45
-19
lines changed

2 files changed

+45
-19
lines changed

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ if(BUILD_TESTING)
4242
find_package(ament_lint_auto REQUIRED)
4343
list(APPEND AMENT_LINT_AUTO_EXCLUDE
4444
ament_cmake_cpplint
45+
ament_cmake_uncrustify
4546
)
4647
set(ament_cmake_clang_format_CONFIG_FILE .clang-format)
4748
ament_lint_auto_find_test_dependencies()

src/marker_server.cpp

Lines changed: 44 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -90,9 +90,12 @@ TwistServerNode::TwistServerNode()
9090
get_node_topics_interface(), get_node_services_interface()))
9191
{
9292
getParameters();
93-
if (use_stamped_msgs) {
93+
if (use_stamped_msgs)
94+
{
9495
vel_stamped_pub = create_publisher<geometry_msgs::msg::TwistStamped>("cmd_vel", 1);
95-
} else {
96+
}
97+
else
98+
{
9699
vel_pub = create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 1);
97100
}
98101
createInteractiveMarkers();
@@ -105,29 +108,41 @@ void TwistServerNode::getParameters()
105108
rclcpp::Parameter robot_name_param;
106109
rclcpp::Parameter use_stamped_msgs_param;
107110

108-
if (this->get_parameter("link_name", link_name_param)) {
111+
if (this->get_parameter("link_name", link_name_param))
112+
{
109113
link_name = link_name_param.as_string();
110-
} else {
114+
}
115+
else
116+
{
111117
link_name = "base_link";
112118
}
113119

114-
if (this->get_parameter("robot_name", robot_name_param)) {
120+
if (this->get_parameter("robot_name", robot_name_param))
121+
{
115122
robot_name = robot_name_param.as_string();
116-
} else {
123+
}
124+
else
125+
{
117126
robot_name = "robot";
118127
}
119128

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+
{
121131
use_stamped_msgs = use_stamped_msgs_param.as_bool();
122-
} else {
132+
}
133+
else
134+
{
123135
use_stamped_msgs = false;
124136
}
125137

126138
// 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+
{
128141
this->get_parameters("max_positive_linear_velocity", max_positive_linear_velocity_map);
129142
this->get_parameters("max_negative_linear_velocity", max_negative_linear_velocity_map);
130-
} else {
143+
}
144+
else
145+
{
131146
linear_drive_scale_map["x"] = 1.0;
132147
max_positive_linear_velocity_map["x"] = 1.0;
133148
max_negative_linear_velocity_map["x"] = -1.0;
@@ -150,7 +165,8 @@ void TwistServerNode::createInteractiveMarkers()
150165

151166
control.orientation_mode = visualization_msgs::msg::InteractiveMarkerControl::FIXED;
152167

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+
{
154170
control.orientation.w = 1;
155171
control.orientation.x = 1;
156172
control.orientation.y = 0;
@@ -160,7 +176,8 @@ void TwistServerNode::createInteractiveMarkers()
160176
interactive_marker.controls.push_back(control);
161177
}
162178

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+
{
164181
control.orientation.w = 1;
165182
control.orientation.x = 0;
166183
control.orientation.y = 0;
@@ -170,7 +187,8 @@ void TwistServerNode::createInteractiveMarkers()
170187
interactive_marker.controls.push_back(control);
171188
}
172189

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+
{
174192
control.orientation.w = 1;
175193
control.orientation.x = 0;
176194
control.orientation.y = 1;
@@ -208,27 +226,33 @@ void TwistServerNode::processFeedback(
208226
vel_msg.angular.z = std::min(vel_msg.angular.z, max_angular_velocity);
209227
vel_msg.angular.z = std::max(vel_msg.angular.z, -max_angular_velocity);
210228

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+
{
212231
vel_msg.linear.x = linear_drive_scale_map["x"] * feedback->pose.position.x;
213232
vel_msg.linear.x = std::min(vel_msg.linear.x, max_positive_linear_velocity_map["x"]);
214233
vel_msg.linear.x = std::max(vel_msg.linear.x, max_negative_linear_velocity_map["x"]);
215234
}
216235

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+
{
218238
vel_msg.linear.y = linear_drive_scale_map["y"] * feedback->pose.position.y;
219239
vel_msg.linear.y = std::min(vel_msg.linear.y, max_positive_linear_velocity_map["y"]);
220240
vel_msg.linear.y = std::max(vel_msg.linear.y, max_negative_linear_velocity_map["y"]);
221241
}
222242

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+
{
224245
vel_msg.linear.z = linear_drive_scale_map["z"] * feedback->pose.position.z;
225246
vel_msg.linear.z = std::min(vel_msg.linear.z, max_positive_linear_velocity_map["z"]);
226247
vel_msg.linear.z = std::max(vel_msg.linear.z, max_negative_linear_velocity_map["z"]);
227248
}
228249

229-
if (use_stamped_msgs) {
250+
if (use_stamped_msgs)
251+
{
230252
stampAndPublish(vel_msg);
231-
} else {
253+
}
254+
else
255+
{
232256
vel_pub->publish(vel_msg);
233257
}
234258

@@ -237,7 +261,8 @@ void TwistServerNode::processFeedback(
237261
server->applyChanges();
238262
}
239263

240-
void TwistServerNode::stampAndPublish(geometry_msgs::msg::Twist &msg) {
264+
void TwistServerNode::stampAndPublish(geometry_msgs::msg::Twist &msg)
265+
{
241266
geometry_msgs::msg::TwistStamped stamped_msg;
242267

243268
stamped_msg.twist = msg;

0 commit comments

Comments
 (0)