42 #include <visualization_msgs/Marker.h>
44 #include <boost/shared_ptr.hpp>
45 #include <boost/make_shared.hpp>
67 void CB_reconfigure(TebLocalPlannerReconfigureConfig& reconfig, uint32_t level);
68 void CB_customObstacle(
const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg);
70 void CB_obstacle_marker(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
72 void CB_via_points(
const nav_msgs::Path::ConstPtr& via_points_msg);
77 int main(
int argc,
char** argv )
90 dynamic_recfg = boost::make_shared< dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig> >(n);
91 dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig>::CallbackType cb = boost::bind(
CB_reconfigure, _1, _2);
106 obst_vector.push_back( boost::make_shared<PointObstacle>(-3,1) );
107 obst_vector.push_back( boost::make_shared<PointObstacle>(6,2) );
108 obst_vector.push_back( boost::make_shared<PointObstacle>(0,0.1) );
114 Eigen::Vector2d vel (0.1, -0.3);
116 vel = Eigen::Vector2d(-0.3, -0.2);
133 std::string topic =
"/test_optim_node/obstacle_" + std::to_string(i) +
"/cmd_vel";
187 visualization_msgs::InteractiveMarker i_marker;
188 i_marker.header.frame_id = frame;
190 std::ostringstream oss;
193 i_marker.name = oss.str();
194 i_marker.description =
"Obstacle";
195 i_marker.pose.position.x = init_x;
196 i_marker.pose.position.y = init_y;
197 i_marker.pose.orientation.w = 1.0f;
200 visualization_msgs::Marker box_marker;
201 box_marker.type = visualization_msgs::Marker::CUBE;
203 box_marker.scale.x = 0.2;
204 box_marker.scale.y = 0.2;
205 box_marker.scale.z = 0.2;
206 box_marker.color.r = 0.5;
207 box_marker.color.g = 0.5;
208 box_marker.color.b = 0.5;
209 box_marker.color.a = 1.0;
210 box_marker.pose.orientation.w = 1.0f;
213 visualization_msgs::InteractiveMarkerControl box_control;
214 box_control.always_visible =
true;
215 box_control.markers.push_back( box_marker );
218 i_marker.controls.push_back( box_control );
221 visualization_msgs::InteractiveMarkerControl move_control;
222 move_control.name =
"move_x";
223 move_control.orientation.w = 0.707107f;
224 move_control.orientation.x = 0;
225 move_control.orientation.y = 0.707107f;
226 move_control.orientation.z = 0;
227 move_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
231 i_marker.controls.push_back(move_control);
234 marker_server->
insert(i_marker);
235 marker_server->
setCallback(i_marker.name,feedback_cb);
240 std::stringstream ss(feedback->marker_name);
247 pobst->position() = Eigen::Vector2d(feedback->pose.position.x,feedback->pose.position.y);
256 for (
size_t i = 0; i < obst_msg->obstacles.size(); ++i)
258 if (obst_msg->obstacles.at(i).polygon.points.size() == 1 )
260 if (obst_msg->obstacles.at(i).radius == 0)
263 obst_msg->obstacles.at(i).polygon.points.front().y )));
268 obst_msg->obstacles.at(i).polygon.points.front().y,
269 obst_msg->obstacles.at(i).radius )));
272 else if (obst_msg->obstacles.at(i).polygon.points.empty())
274 ROS_WARN(
"Invalid custom obstacle received. List of polygon vertices is empty. Skipping...");
280 for (
size_t j=0; j<obst_msg->obstacles.at(i).polygon.points.size(); ++j)
282 polyobst->
pushBackVertex( obst_msg->obstacles.at(i).polygon.points[j].x,
283 obst_msg->obstacles.at(i).polygon.points[j].y );
290 obst_vector.back()->setCentroidVelocity(obst_msg->obstacles.at(i).velocities, obst_msg->obstacles.at(i).orientation);
299 via_points.push_back( Eigen::Vector2d(point_msg->point.x, point_msg->point.y) );
300 ROS_INFO_STREAM(
"Via-point (" << point_msg->point.x <<
"," << point_msg->point.y <<
") added.");
302 ROS_WARN(
"Note, via-points are deactivated, since 'weight_via_point' <= 0");
307 ROS_INFO_ONCE(
"Via-points received. This message is printed once.");
309 for (
const geometry_msgs::PoseStamped& pose : via_points_msg->poses)
311 via_points.emplace_back(pose.pose.position.x, pose.pose.position.y);
319 ROS_WARN(
"Cannot set velocity: unknown obstacle id.");
323 Eigen::Vector2d vel (twist_msg->linear.x, twist_msg->linear.y);