8 private_nh.
param<std::vector<std::string>>(
"waypoint_routines",
27 "setWaypointFollowingMode",
41 "navigationGoalCompleted",
52 "explorationMode", 1);
54 "explorationGoalStatus", 1);
61 "setNavigationToReverse");
91 rsm_msgs::AddWaypoint::Response &res) {
92 if (req.position >= 0 && req.position <
_waypoint_array.waypoints_size) {
95 res.message =
"Added waypoint successfully";
98 res.message =
"Added waypoint successfully at the end";
106 rsm_msgs::GetWaypoints::Response &res) {
112 rsm_msgs::MoveWaypoint::Response &res) {
113 if (req.position >= 0 && req.position <
_waypoint_array.waypoints_size) {
116 res.message =
"Moved waypoint successfully";
119 res.message =
"Position out of waypoint array range";
125 rsm_msgs::RemoveWaypoint::Response &res) {
126 if (req.position >= 0 && req.position <
_waypoint_array.waypoints_size) {
131 res.message =
"Removed waypoint successfully";
134 res.message =
"Position out of waypoint array range";
140 rsm_msgs::WaypointVisited::Response &res) {
141 if (req.position >= 0 && req.position <
_waypoint_array.waypoints_size) {
144 res.message =
"Waypoint visited";
147 res.message =
"Position out of waypoint array range";
153 rsm_msgs::WaypointUnreachable::Request &req,
154 rsm_msgs::WaypointUnreachable::Response &res) {
155 if (req.position >= 0 && req.position <
_waypoint_array.waypoints_size) {
158 res.message =
"Waypoint unreachable";
161 res.message =
"Position out of waypoint array range";
167 std_srvs::Trigger::Response &res) {
170 it.unreachable =
false;
173 res.message =
"Waypoints reset";
178 rsm_msgs::SetWaypointFollowingMode::Request &req,
179 rsm_msgs::SetWaypointFollowingMode::Response &res) {
183 res.message =
"Waypoint Following mode changed";
188 rsm_msgs::SetWaypointRoutine::Request &req,
189 rsm_msgs::SetWaypointRoutine::Response &res) {
190 if (req.position >= 0 && req.position <
_waypoint_array.waypoints_size) {
193 res.message =
"Waypoint routine set";
196 res.message =
"Position out of waypoint array range";
202 rsm_msgs::GetWaypointRoutines::Request &req,
203 rsm_msgs::GetWaypointRoutines::Response &res) {
213 rsm_msgs::SetNavigationGoal::Request &req,
214 rsm_msgs::SetNavigationGoal::Response &res) {
223 res.message =
"Navigation goal set";
228 rsm_msgs::GetNavigationGoal::Request &req,
229 rsm_msgs::GetNavigationGoal::Response &res) {
238 rsm_msgs::GoalCompleted::Request &req,
239 rsm_msgs::GoalCompleted::Response &res) {
243 res.message =
"Exploration goal completed";
247 if (req.status.goal_status == rsm_msgs::GoalStatus::REACHED) {
252 }
else if (req.status.goal_status == rsm_msgs::GoalStatus::FAILED) {
259 res.message =
"Waypoint completed";
263 res.message =
"Navigation goal completed";
272 rsm_msgs::GetRobotPose::Response &res) {
275 geometry_msgs::Pose pose;
288 std_srvs::Trigger::Response &res) {
290 res.message =
"Exploration mode returned";
295 std_srvs::SetBool::Response &res) {
298 res.message =
"Exploration mode set";
313 std_srvs::SetBool::Response &res) {
316 std_srvs::SetBool srv;
319 if (srv.response.success) {
321 res.message =
"Mode set";
324 res.message =
"Mode not set";
327 ROS_ERROR(
"Unable to call Set Navigation To Reverse service");
329 res.message =
"Unable to set reverse mode";
333 res.message =
"Already in requested mode";
339 std_srvs::Trigger::Response &res) {
342 res.message =
"Reverse mode active";
345 res.message =
"Forward mode active";
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::ServiceServer _waypoint_unreachable_service
ros::ServiceServer _get_reverse_mode_service
bool setWaypointRoutine(rsm_msgs::SetWaypointRoutine::Request &req, rsm_msgs::SetWaypointRoutine::Response &res)
std::vector< std::string > _waypoint_routines
ros::ServiceServer _set_exploration_mode_service
void publishExplorationGoalCompleted()
bool resetWaypoints(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
tf::TransformListener _transform_listener
ros::ServiceServer _get_robot_pose_service
ros::ServiceServer _get_navigation_goal_service
void publish(const boost::shared_ptr< M > &message) const
bool NavigationGoalCompleted(rsm_msgs::GoalCompleted::Request &req, rsm_msgs::GoalCompleted::Response &res)
bool getExplorationMode(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
geometry_msgs::Pose _navigation_goal
tf::StampedTransform _transform
ROS transform from map to robot frame.
bool moveWaypoint(rsm_msgs::MoveWaypoint::Request &req, rsm_msgs::MoveWaypoint::Response &res)
bool call(MReq &req, MRes &res)
ros::ServiceClient _set_navigation_to_reverse_client
bool getWaypointRoutines(rsm_msgs::GetWaypointRoutines::Request &req, rsm_msgs::GetWaypointRoutines::Response &res)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool getReverseMode(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer _set_navigation_goal_service
ros::ServiceServer _navigation_goal_completed_service
bool addWaypoint(rsm_msgs::AddWaypoint::Request &req, rsm_msgs::AddWaypoint::Response &res)
ros::Publisher _exploration_goal_publisher
ros::ServiceServer _get_exploration_mode_service
ros::ServiceServer _get_waypoints_service
bool getNavigationGoal(rsm_msgs::GetNavigationGoal::Request &req, rsm_msgs::GetNavigationGoal::Response &res)
TFSIMD_FORCE_INLINE const tfScalar & x() const
bool getRobotPose(rsm_msgs::GetRobotPose::Request &req, rsm_msgs::GetRobotPose::Response &res)
void publishExplorationModes()
ros::ServiceServer _set_waypoint_following_mode_service
ros::Publisher _reverse_mode_publisher
ros::Publisher _exploration_mode_publisher
TFSIMD_FORCE_INLINE const tfScalar & z() const
void publishReverseMode()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::ServiceServer _set_waypoint_routine_service
ros::ServiceServer _get_waypoint_routines_service
bool setNavigationGoal(rsm_msgs::SetNavigationGoal::Request &req, rsm_msgs::SetNavigationGoal::Response &res)
bool getWaypoints(rsm_msgs::GetWaypoints::Request &req, rsm_msgs::GetWaypoints::Response &res)
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::ServiceServer _reset_waypoints_service
std::string _robot_frame
Robot frame id.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
rsm_msgs::WaypointArray _waypoint_array
bool setWaypointFollowingMode(rsm_msgs::SetWaypointFollowingMode::Request &req, rsm_msgs::SetWaypointFollowingMode::Response &res)
bool setExplorationMode(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
ros::ServiceServer _waypoint_visited_service
bool setReverseMode(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
ros::ServiceServer _remove_waypoint_service
bool _reverse_mode_active
ros::ServiceServer _add_waypoint_service
bool removeWaypoint(rsm_msgs::RemoveWaypoint::Request &req, rsm_msgs::RemoveWaypoint::Response &res)
ros::ServiceServer _move_waypoint_service
ros::Publisher _waypoints_publisher
ros::ServiceServer _set_reverse_mode_service
rsm_msgs::GoalStatus _exploration_goal_completed_msg
bool waypointUnreachable(rsm_msgs::WaypointUnreachable::Request &req, rsm_msgs::WaypointUnreachable::Response &res)
bool waypointVisited(rsm_msgs::WaypointVisited::Request &req, rsm_msgs::WaypointVisited::Response &res)