39 #include <geometry_msgs/PoseStamped.h>
40 #include <geometry_msgs/PoseWithCovarianceStamped.h>
42 #include <visualization_msgs/Marker.h>
70 tf_ = std::make_shared<tf2_ros::Buffer>();
71 tf2_ = std::make_shared<tf2_ros::TransformListener>(*
tf_);
72 std::string costmap_class;
73 nh.
param(
"global_costmap_class", costmap_class, std::string(
"nav_core_adapter::CostmapAdapter"));
75 costmap_->initialize(nh, std::string(
"global_costmap"),
tf_);
93 void goalCB(
const geometry_msgs::PoseStamped::ConstPtr& goal)
101 void poseCB(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& goal)
104 start_.header = goal->header;
105 start_.pose.x = goal->pose.pose.position.x;
106 start_.pose.y = goal->pose.pose.position.y;
114 nav_2d_msgs::Path2D
plan;
126 double resolution =
costmap_->getResolution();
128 visualization_msgs::Marker m;
130 m.header.frame_id =
plan.header.frame_id;
132 m.type = visualization_msgs::Marker::LINE_STRIP;
133 m.scale.x = resolution / 4;
138 for (
unsigned int i = 0; i <
plan.poses.size(); i++)
140 m.points.push_back(path.poses[i].pose.position);
144 m.type = visualization_msgs::Marker::SPHERE_LIST;
146 m.color.r =
red_ / 2;
148 m.color.b =
blue_ / 2;
149 m.scale.x = resolution / 2;
150 m.scale.y = resolution / 2;
151 m.scale.z = resolution / 2;
157 visualization_msgs::Marker m;
158 m.header = pose.header;
160 m.ns = (
start ?
"start" :
"goal");
161 m.type = visualization_msgs::Marker::CYLINDER;
162 m.pose.position.x = pose.pose.x;
163 m.pose.position.y = pose.pose.y;
165 double resolution =
costmap_->getResolution();
166 m.scale.x = 4 * resolution;
167 m.scale.y = 4 * resolution;
169 m.color.r =
start ? 0.0 : 1.0;
170 m.color.g =
start ? 1.0 : 0.0;
179 std::shared_ptr<tf2_ros::TransformListener>
tf2_;
192 int main(
int argc,
char** argv)