39 #include <geometry_msgs/PoseStamped.h> 40 #include <geometry_msgs/PoseWithCovarianceStamped.h> 41 #include <visualization_msgs/Marker.h> 70 std::string costmap_class;
71 nh.
param(
"global_costmap_class", costmap_class, std::string(
"nav_core_adapter::CostmapAdapter"));
73 costmap_->initialize(nh, std::string(
"global_costmap"), tf_);
91 void goalCB(
const geometry_msgs::PoseStamped::ConstPtr& goal)
99 void poseCB(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& goal)
102 start_.header = goal->header;
103 start_.pose.x = goal->pose.pose.position.x;
104 start_.pose.y = goal->pose.pose.position.y;
112 nav_2d_msgs::Path2D
plan;
124 double resolution =
costmap_->getResolution();
126 visualization_msgs::Marker
m;
128 m.header.frame_id = plan.header.frame_id;
130 m.type = visualization_msgs::Marker::LINE_STRIP;
131 m.scale.x = resolution / 4;
136 for (
unsigned int i = 0; i < plan.poses.size(); i++)
138 m.points.push_back(path.poses[i].pose.position);
142 m.type = visualization_msgs::Marker::SPHERE_LIST;
144 m.color.r =
red_ / 2;
146 m.color.b =
blue_ / 2;
147 m.scale.x = resolution / 2;
148 m.scale.y = resolution / 2;
149 m.scale.z = resolution / 2;
155 visualization_msgs::Marker
m;
156 m.header = pose.header;
158 m.ns = (start ?
"start" :
"goal");
159 m.type = visualization_msgs::Marker::CYLINDER;
160 m.pose.position.x = pose.pose.x;
161 m.pose.position.y = pose.pose.y;
163 double resolution =
costmap_->getResolution();
164 m.scale.x = 4 * resolution;
165 m.scale.y = 4 * resolution;
167 m.color.r = start ? 0.0 : 1.0;
168 m.color.g = start ? 1.0 : 0.0;
189 int main(
int argc,
char** argv)
ros::Publisher marker_pub_
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Demonstration/debug tool that creates paths between arbitrary points.
nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path &path)
void poseCB(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &goal)
nav_2d_msgs::Pose2DStamped goal_
ROSCPP_DECL void spin(Spinner &spinner)
ros::Subscriber goal_sub_
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
pluginlib::ClassLoader< nav_core2::Costmap > costmap_loader_
int main(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
nav_2d_msgs::Pose2DStamped start_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Plugin-based global wavefront planner that conforms to the nav_core2 GlobalPlanner interface...
void publishPointMarker(nav_2d_msgs::Pose2DStamped pose, bool start)
nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped &start, const nav_2d_msgs::Pose2DStamped &goal) override
ros::Subscriber pose_sub_
nav_core2::Costmap::Ptr costmap_
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr
dlux_global_planner::DluxGlobalPlanner gp_
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)