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);
92 dynamic_recfg->setCallback(cb);
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";
174 planner->visualize();
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 )));
275 for (
size_t j=0; j<obst_msg->obstacles.at(i).polygon.points.size(); ++j)
277 polyobst->
pushBackVertex( obst_msg->obstacles.at(i).polygon.points[j].x,
278 obst_msg->obstacles.at(i).polygon.points[j].y );
285 obst_vector.back()->setCentroidVelocity(obst_msg->obstacles.at(i).velocities, obst_msg->obstacles.at(i).orientation);
294 via_points.push_back( Eigen::Vector2d(point_msg->point.x, point_msg->point.y) );
295 ROS_INFO_STREAM(
"Via-point (" << point_msg->point.x <<
"," << point_msg->point.y <<
") added.");
297 ROS_WARN(
"Note, via-points are deactivated, since 'weight_via_point' <= 0");
302 ROS_INFO_ONCE(
"Via-points received. This message is printed once.");
304 for (
const geometry_msgs::PoseStamped& pose : via_points_msg->poses)
306 via_points.emplace_back(pose.pose.position.x, pose.pose.position.y);
314 ROS_WARN(
"Cannot set velocity: unknown obstacle id.");
318 Eigen::Vector2d vel (twist_msg->linear.x, twist_msg->linear.y);
boost::shared_ptr< PlannerInterface > PlannerInterfacePtr
Abbrev. for shared instances of PlannerInterface or it's subclasses.
Implements a 2D circular obstacle (point obstacle plus radius)
std::string map_frame
Global planning frame.
void finalizePolygon()
Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods...
unsigned int no_fixed_obstacles
#define ROS_INFO_ONCE(...)
void CB_setObstacleVelocity(const geometry_msgs::TwistConstPtr &twist_msg, const unsigned int id)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void CB_reconfigure(TebLocalPlannerReconfigureConfig &reconfig, uint32_t level)
Config class for the teb_local_planner and its components.
ros::Subscriber custom_obst_sub
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Local planner that explores alternative homotopy classes, create a plan for each alternative and fina...
static RobotFootprintModelPtr getRobotFootprintFromParamServer(const ros::NodeHandle &nh)
Get the current robot footprint/contour model.
void CB_obstacle_marker(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
TebVisualizationPtr visual
boost::function< void(const FeedbackConstPtr &) > FeedbackCallback
Implements a polygon obstacle with an arbitrary number of vertices.
void CB_via_points(const nav_msgs::Path::ConstPtr &via_points_msg)
ROSCPP_DECL void spin(Spinner &spinner)
boost::shared_ptr< Obstacle > ObstaclePtr
Abbrev. for shared obstacle pointers.
void CB_mainCycle(const ros::TimerEvent &e)
void CB_customObstacle(const costmap_converter::ObstacleArrayMsg::ConstPtr &obst_msg)
const Eigen::Vector2d & position() const
Return the current position of the obstacle (read-only)
void reconfigure(TebLocalPlannerReconfigureConfig &cfg)
Reconfigure parameters from the dynamic_reconfigure config. Change parameters dynamically (e...
void loadRosParamFromNodeHandle(const ros::NodeHandle &nh)
Load parmeters from the ros param server.
struct teb_local_planner::TebConfig::HomotopyClasses hcp
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
Implements a 2D point obstacle.
PlannerInterfacePtr planner
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
int main(int argc, char **argv)
bool enable_homotopy_class_planning
Activate homotopy class planning (Requires much more resources that simple planning, since multiple trajectories are optimized at once).
std::vector< ros::Subscriber > obst_vel_subs
void pushBackVertex(const Eigen::Ref< const Eigen::Vector2d > &vertex)
Add a vertex to the polygon (edge-point)
ros::Subscriber via_points_sub
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
void CreateInteractiveMarker(const double &init_x, const double &init_y, unsigned int id, std::string frame, interactive_markers::InteractiveMarkerServer *marker_server, interactive_markers::InteractiveMarkerServer::FeedbackCallback feedback_cb)
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
#define ROS_INFO_STREAM(args)
INTERACTIVE_MARKERS_PUBLIC void applyChanges()
INTERACTIVE_MARKERS_PUBLIC bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
std::vector< ObstaclePtr > obst_vector
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
ros::Subscriber clicked_points_sub
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
ViaPointContainer via_points
void CB_clicked_points(const geometry_msgs::PointStampedConstPtr &point_msg)
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
void CB_publishCycle(const ros::TimerEvent &e)
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
Typedef for a container storing via-points.
boost::shared_ptr< dynamic_reconfigure::Server< TebLocalPlannerReconfigureConfig > > dynamic_recfg