#include <auto_docking_ros.hpp>
Public Member Functions | |
AutoDockingROS (std::string name) | |
bool | init (ros::NodeHandle &nh) |
void | spin () |
~AutoDockingROS () | |
Private Member Functions | |
void | debugCb (const std_msgs::StringConstPtr &msg) |
void | goalCb () |
void | preemptCb () |
void | syncCb (const nav_msgs::OdometryConstPtr &odom, const kobuki_msgs::SensorStateConstPtr &core, const kobuki_msgs::DockInfraRedConstPtr &ir) |
Private Attributes | |
actionlib::SimpleActionServer< kobuki_msgs::AutoDockingAction > | as_ |
boost::shared_ptr< message_filters::Subscriber< kobuki_msgs::SensorState > > | core_sub_ |
ros::Subscriber | debug_ |
ros::Publisher | debug_jabber_ |
DockDrive | dock_ |
kobuki_msgs::AutoDockingFeedback | feedback_ |
kobuki_msgs::AutoDockingGoal | goal_ |
boost::shared_ptr< message_filters::Subscriber< kobuki_msgs::DockInfraRed > > | ir_sub_ |
ros::Publisher | motor_power_enabler_ |
std::string | name_ |
ros::NodeHandle | nh_ |
boost::shared_ptr< message_filters::Subscriber< nav_msgs::Odometry > > | odom_sub_ |
kobuki_msgs::AutoDockingResult | result_ |
AutoDockingROS * | self |
bool | shutdown_requested_ |
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > | sync_ |
ros::Publisher | velocity_commander_ |
Definition at line 52 of file auto_docking_ros.hpp.
kobuki::AutoDockingROS::AutoDockingROS | ( | std::string | name | ) |
Definition at line 19 of file auto_docking_ros.cpp.
kobuki::AutoDockingROS::~AutoDockingROS | ( | ) |
Definition at line 33 of file auto_docking_ros.cpp.
|
private |
Definition at line 164 of file auto_docking_ros.cpp.
|
private |
Definition at line 75 of file auto_docking_ros.cpp.
bool kobuki::AutoDockingROS::init | ( | ros::NodeHandle & | nh | ) |
Definition at line 43 of file auto_docking_ros.cpp.
|
private |
Definition at line 89 of file auto_docking_ros.cpp.
void kobuki::AutoDockingROS::spin | ( | ) |
Definition at line 68 of file auto_docking_ros.cpp.
|
private |
Definition at line 105 of file auto_docking_ros.cpp.
|
private |
Definition at line 72 of file auto_docking_ros.hpp.
|
private |
Definition at line 83 of file auto_docking_ros.hpp.
|
private |
Definition at line 78 of file auto_docking_ros.hpp.
|
private |
Definition at line 79 of file auto_docking_ros.hpp.
|
private |
Definition at line 66 of file auto_docking_ros.hpp.
|
private |
Definition at line 75 of file auto_docking_ros.hpp.
|
private |
Definition at line 74 of file auto_docking_ros.hpp.
|
private |
Definition at line 82 of file auto_docking_ros.hpp.
|
private |
Definition at line 79 of file auto_docking_ros.hpp.
|
private |
Definition at line 68 of file auto_docking_ros.hpp.
|
private |
Definition at line 71 of file auto_docking_ros.hpp.
|
private |
Definition at line 81 of file auto_docking_ros.hpp.
|
private |
Definition at line 76 of file auto_docking_ros.hpp.
|
private |
Definition at line 65 of file auto_docking_ros.hpp.
|
private |
Definition at line 69 of file auto_docking_ros.hpp.
|
private |
Definition at line 84 of file auto_docking_ros.hpp.
|
private |
Definition at line 79 of file auto_docking_ros.hpp.