57 const fastrack_msgs::ReplanRequest::ConstPtr& msg) {
60 ROS_ERROR(
"%s: Replan server was disconnected.",
name_.c_str());
65 fastrack_srvs::Replan replan;
66 replan.request.req = *msg;
68 ROS_ERROR(
"%s: Replan server error.",
name_.c_str());
69 replan.response.traj.states.clear();
70 replan.response.traj.times.clear();
79 name_ = ros::names::append(n.getNamespace(),
"Replanner");
83 ROS_ERROR(
"%s: Failed to load parameters.",
name_.c_str());
89 ROS_ERROR(
"%s: Failed to register callbacks.",
name_.c_str());
99 ros::NodeHandle nl(n);
102 if (!nl.getParam(
"topic/traj",
traj_topic_))
return false;
113 ros::NodeHandle nl(n);
116 traj_pub_ = nl.advertise<fastrack_msgs::Trajectory>(
125 replan_srv_ = nl.serviceClient<fastrack_srvs::Replan>(
ros::ServiceClient replan_srv_
void ReplanRequestCallback(const fastrack_msgs::ReplanRequest::ConstPtr &msg)
bool LoadParameters(const ros::NodeHandle &n)
bool Initialize(const ros::NodeHandle &n)
std::string replan_srv_name_
std::string replan_request_topic_
bool RegisterCallbacks(const ros::NodeHandle &n)
ros::Subscriber replan_request_sub_