#include <dock_server.h>

Public Types | |
| typedef actionlib::ServerGoalHandle< caster_app::DockAction > | GoalHandle |
Public Types inherited from actionlib::ActionServer< caster_app::DockAction > | |
| typedef ServerGoalHandle< caster_app::DockAction > | GoalHandle |
Public Types inherited from actionlib::ActionServerBase< ActionSpec > | |
| typedef ServerGoalHandle< ActionSpec > | GoalHandle |
Public Member Functions | |
| bool | docked () |
| DockServer (ros::NodeHandle &nh, ros::NodeHandle &private_nh, const std::string &server_name) | |
| void | Initialize () |
Public Member Functions inherited from actionlib::ActionServer< caster_app::DockAction > | |
| ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start) | |
| ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, bool auto_start) | |
| ROS_DEPRECATED | ActionServer (ros::NodeHandle n, std::string name) |
| ActionServer (ros::NodeHandle n, std::string name, bool auto_start) | |
| ROS_DEPRECATED | ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb=boost::function< void(GoalHandle)>()) |
| virtual | ~ActionServer () |
Public Member Functions inherited from actionlib::ActionServerBase< ActionSpec > | |
| ActionServerBase (boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start=false) | |
| void | cancelCallback (const boost::shared_ptr< const actionlib_msgs::GoalID > &goal_id) |
| void | goalCallback (const boost::shared_ptr< const ActionGoal > &goal) |
| void | registerCancelCallback (boost::function< void(GoalHandle)> cb) |
| void | registerGoalCallback (boost::function< void(GoalHandle)> cb) |
| void | start () |
| virtual | ~ActionServerBase () |
Private Member Functions | |
| void | CancelCallback (GoalHandle gh) |
| void | GoalCallback (GoalHandle gh) |
| void | MovebaseDoneCallback (const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result) |
| void | MovebaseFeedbackCallback (const move_base_msgs::MoveBaseFeedbackConstPtr &feedback) |
| void | MoveToDock () |
| void | MoveToDockReady () |
| void | UnDock () |
Private Attributes | |
| std::string | action_name_ |
| std::string | base_frame_ |
| ros::Publisher | cmd_pub_ |
| float | dock_distance_ |
| geometry_msgs::Pose | dock_ready_pose_ |
| float | dock_speed_ |
| bool | docked_ |
| caster_app::DockFeedback | feedback_ |
| GoalHandle | goal_ |
| std::string | map_frame_ |
| actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > | move_base_client_ |
| ros::NodeHandle | nh_ |
| std::string | odom_frame_ |
| DockPerception | perception_ |
| ros::NodeHandle | private_nh_ |
| caster_app::DockResult | result_ |
| tf::TransformListener | tf_listener_ |
Additional Inherited Members | |
Protected Attributes inherited from actionlib::ActionServerBase< ActionSpec > | |
| boost::function< void(GoalHandle)> | cancel_callback_ |
| boost::function< void(GoalHandle)> | goal_callback_ |
| boost::shared_ptr< DestructionGuard > | guard_ |
| GoalIDGenerator | id_generator_ |
| ros::Time | last_cancel_ |
| boost::recursive_mutex | lock_ |
| bool | started_ |
| std::list< StatusTracker< ActionSpec > > | status_list_ |
| ros::Duration | status_list_timeout_ |
Definition at line 19 of file dock_server.h.
| typedef actionlib::ServerGoalHandle<caster_app::DockAction> iqr::DockServer::GoalHandle |
Definition at line 62 of file dock_server.h.
| iqr::DockServer::DockServer | ( | ros::NodeHandle & | nh, |
| ros::NodeHandle & | private_nh, | ||
| const std::string & | server_name | ||
| ) |
Definition at line 3 of file dock_server.cpp.
|
private |
Definition at line 245 of file dock_server.cpp.
|
inline |
Definition at line 68 of file dock_server.h.
|
private |
Definition at line 187 of file dock_server.cpp.
| void iqr::DockServer::Initialize | ( | ) |
Definition at line 35 of file dock_server.cpp.
|
private |
Definition at line 156 of file dock_server.cpp.
|
private |
Definition at line 167 of file dock_server.cpp.
|
private |
Definition at line 93 of file dock_server.cpp.
|
private |
Definition at line 144 of file dock_server.cpp.
|
private |
Definition at line 42 of file dock_server.cpp.
|
private |
Definition at line 23 of file dock_server.h.
|
private |
Definition at line 46 of file dock_server.h.
|
private |
Definition at line 35 of file dock_server.h.
|
private |
Definition at line 43 of file dock_server.h.
|
private |
Definition at line 48 of file dock_server.h.
|
private |
Definition at line 42 of file dock_server.h.
|
private |
Definition at line 21 of file dock_server.h.
|
private |
Definition at line 31 of file dock_server.h.
|
private |
Definition at line 28 of file dock_server.h.
|
private |
Definition at line 44 of file dock_server.h.
|
private |
Definition at line 37 of file dock_server.h.
|
private |
Definition at line 25 of file dock_server.h.
|
private |
Definition at line 45 of file dock_server.h.
|
private |
Definition at line 39 of file dock_server.h.
|
private |
Definition at line 26 of file dock_server.h.
|
private |
Definition at line 30 of file dock_server.h.
|
private |
Definition at line 33 of file dock_server.h.