33 #include <visualization_msgs/Marker.h>
49 void CB_obstacle_marker(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
50 void CB_customObstacle(
const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg);
52 void CB_via_points(
const nav_msgs::Path::ConstPtr& via_points_msg);
56 std::vector<teb_local_planner::PoseSE2>
_via_points;
61 std::string map_frame =
"map";
67 _obstacles.push_back(boost::make_shared<teb_local_planner::PointObstacle>(-3, 1));
68 _obstacles.push_back(boost::make_shared<teb_local_planner::PointObstacle>(6, 2));
69 _obstacles.push_back(boost::make_shared<teb_local_planner::PointObstacle>(4, 0.1));
99 ROS_ERROR(
"Controller configuration failed.");
111 geometry_msgs::Twist vel;
113 bool success =
false;
121 publisher.publishLocalPlan(*x_seq);
126 publisher.publishRobotFootprintModel(x0, *robot_model);
137 visualization_msgs::InteractiveMarker i_marker;
138 i_marker.header.frame_id = frame;
140 std::ostringstream oss;
143 i_marker.name = oss.str();
144 i_marker.description =
"Obstacle";
145 i_marker.pose.position.x = init_x;
146 i_marker.pose.position.y = init_y;
147 i_marker.pose.orientation.w = 1.0f;
150 visualization_msgs::Marker box_marker;
151 box_marker.type = visualization_msgs::Marker::CUBE;
153 box_marker.scale.x = 0.2;
154 box_marker.scale.y = 0.2;
155 box_marker.scale.z = 0.2;
156 box_marker.color.r = 0.5;
157 box_marker.color.g = 0.5;
158 box_marker.color.b = 0.5;
159 box_marker.color.a = 1.0;
160 box_marker.pose.orientation.w = 1.0f;
163 visualization_msgs::InteractiveMarkerControl box_control;
164 box_control.always_visible =
true;
165 box_control.markers.push_back(box_marker);
168 i_marker.controls.push_back(box_control);
171 visualization_msgs::InteractiveMarkerControl move_control;
172 move_control.name =
"move_x";
173 move_control.orientation.w = 0.707107f;
174 move_control.orientation.x = 0;
175 move_control.orientation.y = 0.707107f;
176 move_control.orientation.z = 0;
177 move_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
180 i_marker.controls.push_back(move_control);
183 marker_server->
insert(i_marker);
189 std::stringstream ss(feedback->marker_name);
195 pobst->position() = Eigen::Vector2d(feedback->pose.position.x, feedback->pose.position.y);
204 for (
size_t i = 0; i < obst_msg->obstacles.size(); ++i)
206 if (obst_msg->obstacles.at(i).polygon.points.size() == 1)
208 if (obst_msg->obstacles.at(i).radius == 0)
211 obst_msg->obstacles.at(i).polygon.points.front().x, obst_msg->obstacles.at(i).polygon.points.front().y)));
217 obst_msg->obstacles.at(i).polygon.points.front().y, obst_msg->obstacles.at(i).radius)));
223 for (
size_t j = 0; j < obst_msg->obstacles.at(i).polygon.points.size(); ++j)
225 polyobst->
pushBackVertex(obst_msg->obstacles.at(i).polygon.points[j].x, obst_msg->obstacles.at(i).polygon.points[j].y);
231 if (!
_obstacles.empty())
_obstacles.back()->setCentroidVelocity(obst_msg->obstacles.at(i).velocities, obst_msg->obstacles.at(i).orientation);
239 _via_points.emplace_back(point_msg->point.x, point_msg->point.y, 0.0);
240 ROS_INFO_STREAM(
"Via-point (" << point_msg->point.x <<
"," << point_msg->point.y <<
") added.");
245 ROS_INFO_ONCE(
"Via-points received. This message is printed once.");
247 for (
const geometry_msgs::PoseStamped& pose : via_points_msg->poses)
249 _via_points.emplace_back(pose.pose.position.x, pose.pose.position.y, 0);
253 int main(
int argc,
char** argv)
255 ros::init(argc, argv,
"test_optim_node");