Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
iqr::DockServer Class Reference

#include <dock_server.h>

Inheritance diagram for iqr::DockServer:
Inheritance graph
[legend]

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< DestructionGuardguard_
 
GoalIDGenerator id_generator_
 
ros::Time last_cancel_
 
boost::recursive_mutex lock_
 
bool started_
 
std::list< StatusTracker< ActionSpec > > status_list_
 
ros::Duration status_list_timeout_
 

Detailed Description

Definition at line 19 of file dock_server.h.

Member Typedef Documentation

Definition at line 62 of file dock_server.h.

Constructor & Destructor Documentation

iqr::DockServer::DockServer ( ros::NodeHandle nh,
ros::NodeHandle private_nh,
const std::string &  server_name 
)

Definition at line 3 of file dock_server.cpp.

Member Function Documentation

void iqr::DockServer::CancelCallback ( GoalHandle  gh)
private

Definition at line 245 of file dock_server.cpp.

bool iqr::DockServer::docked ( )
inline

Definition at line 68 of file dock_server.h.

void iqr::DockServer::GoalCallback ( GoalHandle  gh)
private

Definition at line 187 of file dock_server.cpp.

void iqr::DockServer::Initialize ( )

Definition at line 35 of file dock_server.cpp.

void iqr::DockServer::MovebaseDoneCallback ( const actionlib::SimpleClientGoalState state,
const move_base_msgs::MoveBaseResultConstPtr &  result 
)
private

Definition at line 156 of file dock_server.cpp.

void iqr::DockServer::MovebaseFeedbackCallback ( const move_base_msgs::MoveBaseFeedbackConstPtr &  feedback)
private

Definition at line 167 of file dock_server.cpp.

void iqr::DockServer::MoveToDock ( )
private

Definition at line 93 of file dock_server.cpp.

void iqr::DockServer::MoveToDockReady ( )
private

Definition at line 144 of file dock_server.cpp.

void iqr::DockServer::UnDock ( )
private

Definition at line 42 of file dock_server.cpp.

Member Data Documentation

std::string iqr::DockServer::action_name_
private

Definition at line 23 of file dock_server.h.

std::string iqr::DockServer::base_frame_
private

Definition at line 46 of file dock_server.h.

ros::Publisher iqr::DockServer::cmd_pub_
private

Definition at line 35 of file dock_server.h.

float iqr::DockServer::dock_distance_
private

Definition at line 43 of file dock_server.h.

geometry_msgs::Pose iqr::DockServer::dock_ready_pose_
private

Definition at line 48 of file dock_server.h.

float iqr::DockServer::dock_speed_
private

Definition at line 42 of file dock_server.h.

bool iqr::DockServer::docked_
private

Definition at line 21 of file dock_server.h.

caster_app::DockFeedback iqr::DockServer::feedback_
private

Definition at line 31 of file dock_server.h.

GoalHandle iqr::DockServer::goal_
private

Definition at line 28 of file dock_server.h.

std::string iqr::DockServer::map_frame_
private

Definition at line 44 of file dock_server.h.

actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> iqr::DockServer::move_base_client_
private

Definition at line 37 of file dock_server.h.

ros::NodeHandle iqr::DockServer::nh_
private

Definition at line 25 of file dock_server.h.

std::string iqr::DockServer::odom_frame_
private

Definition at line 45 of file dock_server.h.

DockPerception iqr::DockServer::perception_
private

Definition at line 39 of file dock_server.h.

ros::NodeHandle iqr::DockServer::private_nh_
private

Definition at line 26 of file dock_server.h.

caster_app::DockResult iqr::DockServer::result_
private

Definition at line 30 of file dock_server.h.

tf::TransformListener iqr::DockServer::tf_listener_
private

Definition at line 33 of file dock_server.h.


The documentation for this class was generated from the following files:


caster_app
Author(s): Ye Tian
autogenerated on Wed Dec 18 2019 03:34:44