44 #include <geometry_msgs/Twist.h> 46 #include <nav_msgs/Path.h> 48 #include <trajectory_tracker_msgs/ChangePath.h> 49 #include <trajectory_tracker_msgs/TrajectoryServerStatus.h> 50 #include <visualization_msgs/InteractiveMarkerUpdate.h> 73 trajectory_tracker_msgs::ChangePath::Request
req_path_;
82 bool change(trajectory_tracker_msgs::ChangePath::Request& req,
83 trajectory_tracker_msgs::ChangePath::Response& res);
85 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
108 pub_path_ = neonavigation_common::compat::advertise<nav_msgs::Path>(
111 pub_status_ = pnh_.advertise<trajectory_tracker_msgs::TrajectoryServerStatus>(
"status", 2);
124 std::ifstream ifs(
req_path_.filename.c_str());
127 ifs.seekg(0, ifs.end);
129 ifs.seekg(0, ifs.beg);
131 ifs.read(reinterpret_cast<char*>(
buffer_.get()), serial_size_);
139 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
141 int id = std::atoi(feedback->marker_name.c_str());
142 switch (feedback->event_type)
144 case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
145 path_.poses[id].pose = feedback->pose;
147 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
151 case visualization_msgs::InteractiveMarkerFeedback::MENU_SELECT:
152 switch (feedback->menu_entry_id)
169 visualization_msgs::InteractiveMarkerUpdate viz;
170 viz.type = viz.KEEP_ALIVE;
172 viz.server_id =
"Path";
175 for (
auto& p :
path_.poses)
177 visualization_msgs::InteractiveMarker mark;
178 visualization_msgs::Marker marker;
179 visualization_msgs::InteractiveMarkerControl ctl;
180 visualization_msgs::MenuEntry menu;
181 mark.header =
path_.header;
184 std::stringstream ss;
186 mark.name = ss.str();
189 marker.scale.x = 0.2;
190 marker.scale.y = 0.05;
191 marker.scale.z = 0.05;
196 marker.type = marker.ARROW;
200 ctl.interaction_mode = ctl.MOVE_ROTATE;
201 ctl.orientation_mode = ctl.INHERIT;
202 ctl.always_visible =
true;
203 ctl.markers.push_back(marker);
205 mark.controls.push_back(ctl);
208 ctl.interaction_mode = ctl.MENU;
210 marker.type = marker.SPHERE;
213 marker.scale.x = 0.08;
214 marker.scale.y = 0.08;
215 marker.scale.z = 0.08;
216 ctl.markers[0] = marker;
217 mark.controls.push_back(ctl);
221 menu.title =
"Delete";
222 menu.command_type = menu.FEEDBACK;
223 mark.menu_entries.push_back(menu);
228 mark.menu_entries.push_back(menu);
230 viz.markers.push_back(mark);
236 trajectory_tracker_msgs::ChangePath::Response& res)
255 for (
size_t i = 0; i <
path_.poses.size(); i++)
257 path_.poses[i].pose.position.x =
lpf_[0]->
in(
path_.poses[i].pose.position.x);
258 path_.poses[i].pose.position.y =
lpf_[1]->
in(
path_.poses[i].pose.position.y);
273 path_.header.frame_id =
"map";
281 trajectory_tracker_msgs::TrajectoryServerStatus status;
285 status.header =
path_.header;
294 int main(
int argc,
char** argv)
296 ros::init(argc, argv,
"trajectory_server");
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
bool change(trajectory_tracker_msgs::ChangePath::Request &req, trajectory_tracker_msgs::ChangePath::Response &res)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
ros::ServiceServer srv_change_path_
ros::ServiceServer advertiseService(ros::NodeHandle &nh_new, const std::string &service_new, ros::NodeHandle &nh_old, const std::string &service_old, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
boost::shared_array< uint8_t > buffer_
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
INTERACTIVE_MARKERS_PUBLIC void applyChanges()
interactive_markers::InteractiveMarkerServer srv_im_fb_
trajectory_tracker::Filter * lpf_[2]
INTERACTIVE_MARKERS_PUBLIC void clear()
ros::Publisher pub_status_
trajectory_tracker_msgs::ChangePath::Request req_path_
ROSCPP_DECL void spinOnce()
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T ¶m, const T &default_value)
void deserialize(Stream &stream, T &t)