auto_docking_ros.cpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10 ** Includes
11 *****************************************************************************/
12 
14 
15 namespace kobuki
16 {
17 
18 //AutoDockingROS::AutoDockingROS()
20 //AutoDockingROS::AutoDockingROS(ros::NodeHandle& nh)
21 //AutoDockingROS::AutoDockingROS(ros::NodeHandle& nh, std::string name)
22  : name_(name)
23  , shutdown_requested_(false)
24  , as_(nh_, name_+"_action", false)
25 {
26  self = this;
27 
28  as_.registerGoalCallback(boost::bind(&AutoDockingROS::goalCb, this));
30  as_.start();
31 }
32 
34 {
35  shutdown_requested_ = true;
36  if (as_.isActive()) {
37  result_.text = "Aborted: Shutdown requested.";
38  as_.setAborted( result_, result_.text );
39  }
40  dock_.disable();
41 }
42 
44 {
45  // Configure docking drive
46  double min_abs_v, min_abs_w;
47  if (nh.getParam("min_abs_v", min_abs_v) == true)
48  dock_.setMinAbsV(min_abs_v);
49 
50  if (nh.getParam("min_abs_w", min_abs_w) == true)
51  dock_.setMinAbsW(min_abs_w);
52 
53  // Publishers and subscribers
54  velocity_commander_ = nh.advertise<geometry_msgs::Twist>("velocity", 10);
55  debug_jabber_ = nh.advertise<std_msgs::String>("debug/feedback", 10);
56 
57  debug_ = nh.subscribe("debug/mode_shift", 10, &AutoDockingROS::debugCb, this);
58 
63  sync_->registerCallback(boost::bind(&AutoDockingROS::syncCb, this, _1, _2, _3));
64 
65  return dock_.init();
66 }
67 
69 {
70  return;
71 
72  while(!shutdown_requested_){;}
73 }
74 
76 {
77  if (dock_.isEnabled()) {
78  goal_ = *(as_.acceptNewGoal());
79  result_.text = "Rejected: dock_drive is already enabled.";
80  as_.setAborted( result_, result_.text );
81  ROS_INFO_STREAM("[" << name_ << "] New goal received but rejected.");
82  } else {
83  dock_.enable();
84  goal_ = *(as_.acceptNewGoal());
85  ROS_INFO_STREAM("[" << name_ << "] New goal received and accepted.");
86  }
87 }
88 
90 {
91  //ROS_DEBUG_STREAM("[" << name_ << "] Preempt requested.");
92  dock_.disable();
93  if (as_.isNewGoalAvailable()) {
94  result_.text = "Preempted: New goal received.";
96  ROS_INFO_STREAM("[" << name_ << "] " << result_.text );
97  } else {
98  result_.text = "Cancelled: Cancel requested.";
100  ROS_INFO_STREAM("[" << name_ << "] " << result_.text );
101  dock_.disable();
102  }
103 }
104 
105 void AutoDockingROS::syncCb(const nav_msgs::OdometryConstPtr& odom,
106  const kobuki_msgs::SensorStateConstPtr& core,
107  const kobuki_msgs::DockInfraRedConstPtr& ir)
108 {
109  //process and run
110  if(self->dock_.isEnabled()) {
111  //conversions
112  KDL::Rotation rot;
113  tf::quaternionMsgToKDL( odom->pose.pose.orientation, rot );
114 
115  double r, p, y;
116  rot.GetRPY(r, p, y);
117 
119  pose.x(odom->pose.pose.position.x);
120  pose.y(odom->pose.pose.position.y);
121  pose.heading(y);
122 
123  //update
124  self->dock_.update(ir->data, core->bumper, core->charger, pose);
125 
126  //publish debug stream
127  std_msgs::StringPtr debug_log(new std_msgs::String);
128  debug_log->data = self->dock_.getDebugStream();
129  debug_jabber_.publish(debug_log);
130 
131  //publish command velocity
132  if (self->dock_.canRun()) {
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();
136  velocity_commander_.publish(cmd_vel);
137  }
138  }
139 
140  //action server execution
141  if( as_.isActive() ) {
143  result_.text = "Arrived on docking station successfully.";
145  ROS_INFO_STREAM( "[" << name_ << "]: Arrived on docking station successfully.");
146  ROS_DEBUG_STREAM( "[" << name_ << "]: Result sent.");
147  dock_.disable();
148  } else if ( !dock_.isEnabled() ) { //Action Server is activated, but DockDrive is not enabled, or disabled unexpectedly
149  ROS_ERROR_STREAM("[" << name_ << "] Unintended Case: ActionService is active, but DockDrive is not enabled..");
150  result_.text = "Aborted: dock_drive is disabled unexpectedly.";
151  as_.setAborted( result_, "Aborted: dock_drive is disabled unexpectedly." );
152  ROS_INFO_STREAM("[" << name_ << "] Goal aborted.");
153  dock_.disable();
154  } else {
155  feedback_.state = dock_.getStateStr();
156  feedback_.text = dock_.getDebugStr();
158  ROS_DEBUG_STREAM( "[" << name_ << "]: Feedback sent.");
159  }
160  }
161  return;
162 }
163 
164 void AutoDockingROS::debugCb(const std_msgs::StringConstPtr& msg)
165 {
166  dock_.modeShift(msg->data);
167 }
168 
169 
170 } //namespace kobuki
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_
bool isEnabled() const
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)
bool canRun() const
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_


kobuki_auto_docking
Author(s): Younghun Ju
autogenerated on Mon Jun 10 2019 13:44:57