23 , shutdown_requested_(false)
24 , as_(nh_, name_+
"_action", false)
37 result_.text =
"Aborted: Shutdown requested.";
46 double min_abs_v, min_abs_w;
47 if (nh.
getParam(
"min_abs_v", min_abs_v) ==
true)
50 if (nh.
getParam(
"min_abs_w", min_abs_w) ==
true)
79 result_.text =
"Rejected: dock_drive is already enabled.";
94 result_.text =
"Preempted: New goal received.";
98 result_.text =
"Cancelled: Cancel requested.";
106 const kobuki_msgs::SensorStateConstPtr& core,
107 const kobuki_msgs::DockInfraRedConstPtr& ir)
119 pose.x(odom->pose.pose.position.x);
120 pose.y(odom->pose.pose.position.y);
124 self->dock_.update(ir->data, core->bumper, core->charger, pose);
127 std_msgs::StringPtr debug_log(
new std_msgs::String);
128 debug_log->data =
self->dock_.getDebugStream();
133 geometry_msgs::TwistPtr cmd_vel(
new geometry_msgs::Twist);
134 cmd_vel->linear.x =
self->dock_.getVX();
135 cmd_vel->angular.z =
self->dock_.getWZ();
143 result_.text =
"Arrived on docking station successfully.";
149 ROS_ERROR_STREAM(
"[" <<
name_ <<
"] Unintended Case: ActionService is active, but DockDrive is not enabled..");
150 result_.text =
"Aborted: dock_drive is disabled unexpectedly.";
ros::Publisher debug_jabber_
boost::shared_ptr< const Goal > acceptNewGoal()
void publishFeedback(const FeedbackConstPtr &feedback)
void setMinAbsV(double mav)
boost::shared_ptr< message_filters::Subscriber< nav_msgs::Odometry > > odom_sub_
kobuki_msgs::AutoDockingGoal goal_
void modeShift(const std::string &mode)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
kobuki_msgs::AutoDockingFeedback feedback_
message_filters::sync_policies::ApproximateTime< nav_msgs::Odometry, kobuki_msgs::SensorState, kobuki_msgs::DockInfraRed > SyncPolicy
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
std::string getStateStr() const
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< message_filters::Subscriber< kobuki_msgs::SensorState > > core_sub_
RobotDockingState::State getState() const
std::string getDebugStr() const
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
void syncCb(const nav_msgs::OdometryConstPtr &odom, const kobuki_msgs::SensorStateConstPtr &core, const kobuki_msgs::DockInfraRedConstPtr &ir)
void quaternionMsgToKDL(const geometry_msgs::Quaternion &m, KDL::Rotation &k)
void registerPreemptCallback(boost::function< void()> cb)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_DEBUG_STREAM(args)
void GetRPY(double &roll, double &pitch, double &yaw) const
kobuki_msgs::AutoDockingResult result_
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
#define ROS_INFO_STREAM(args)
void setMinAbsW(double maw)
bool getParam(const std::string &key, std::string &s) const
AutoDockingROS(std::string name)
actionlib::SimpleActionServer< kobuki_msgs::AutoDockingAction > as_
bool init(ros::NodeHandle &nh)
#define ROS_ERROR_STREAM(args)
void registerGoalCallback(boost::function< void()> cb)
ros::Publisher velocity_commander_
void debugCb(const std_msgs::StringConstPtr &msg)
boost::shared_ptr< message_filters::Subscriber< kobuki_msgs::DockInfraRed > > ir_sub_
bool isNewGoalAvailable()