33 #include <move_base_msgs/MoveBaseAction.h> 35 #include <geometry_msgs/Twist.h> 36 #include <geometry_msgs/PoseStamped.h> 37 #include <nav_msgs/Odometry.h> 38 #include <cob_srvs/SetString.h> 69 m_mutex = PTHREAD_MUTEX_INITIALIZER;
74 topic_pub_command_ = nh_.
advertise<geometry_msgs::Twist>(
"cmd_vel", 1);
80 goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>(
"goal", 1, boost::bind(&
NodeClass::topicCB,
this, _1));
85 odometry_sub_ = nh_.subscribe<nav_msgs::Odometry>(
"odom", 1, boost::bind(&
NodeClass::odometryCB,
this, _1));
90 if(!private_nh.
hasParam(
"kv"))
ROS_WARN(
"Used default parameter for kv [2.5]");
93 if(!private_nh.
hasParam(
"kp"))
ROS_WARN(
"Used default parameter for kp [3.0]");
96 if(!private_nh.
hasParam(
"virt_mass"))
ROS_WARN(
"Used default parameter for virt_mass [0.5]");
99 if(!private_nh.
hasParam(
"vmax"))
ROS_WARN(
"Used default parameter for vmax [0.3 m/s]");
102 if(!private_nh.
hasParam(
"goal_threshold"))
ROS_WARN(
"Used default parameter for goal_threshold [0.03 cm]");
105 if(!private_nh.
hasParam(
"speed_threshold"))
ROS_WARN(
"Used default parameter for speed_threshold [0.08 m/s]");
108 if(!private_nh.
hasParam(
"kv_rot"))
ROS_WARN(
"Used default parameter for kv_rot [2.0]");
111 if(!private_nh.
hasParam(
"kp_rot"))
ROS_WARN(
"Used default parameter for kp_rot [2.0]");
114 if(!private_nh.
hasParam(
"virt_mass_rot"))
ROS_WARN(
"Used default parameter for virt_mass_rot [0.5]");
117 if(!private_nh.
hasParam(
"vtheta_max"))
ROS_WARN(
"Used default parameter for vtheta_max [0.3 rad/s]");
120 if(!private_nh.
hasParam(
"goal_threshold_rot"))
ROS_WARN(
"Used default parameter for goal_threshold_rot [0.08 rad]");
123 if(!private_nh.
hasParam(
"speed_threshold_rot"))
ROS_WARN(
"Used default parameter for speed_threshold_rot [0.08 rad/s]");
126 if(!private_nh.
hasParam(
"goal_abortion_speed"))
ROS_WARN(
"Used default parameter for goal_abortion_speed [0.01 m/s]");
129 if(!private_nh.
hasParam(
"goal_abortion_speed_rot"))
ROS_WARN(
"Used default parameter for goal_abortion_speed_rot [0.01 rad/s]");
132 if(!private_nh.
hasParam(
"global_frame"))
ROS_WARN(
"Used default parameter for global_frame [/map]");
135 if(!private_nh.
hasParam(
"robot_frame"))
ROS_WARN(
"Used default parameter for robot_frame [/base_link]");
138 if(!private_nh.
hasParam(
"robot_footprint_frame"))
ROS_WARN(
"Used default parameter for robot_footprint_frame [/base_footprint]");
141 if(!private_nh.
hasParam(
"slow_down_distance"))
ROS_WARN(
"Used default parameter for slow_down_distance [0.5m]");
144 if(!private_nh.
hasParam(
"goal_abortion_time"))
ROS_WARN(
"Used default parameter for goal_abortion_time [5.0s]");
147 if(!private_nh.
hasParam(
"use_move_action"))
ROS_WARN(
"Used default parameter for use_move_action [true]");
174 void topicCB(
const geometry_msgs::PoseStamped::ConstPtr& goal)
182 ROS_INFO(
"In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
183 move_base_msgs::MoveBaseGoal action_goal;
187 action_client_->
sendGoal(action_goal);
192 ROS_DEBUG(
"In ROS goal callback, using the PoseStamped as error and start control step.");
218 void actionCB(
const move_base_msgs::MoveBaseGoalConstPtr &goal)
222 as_.
setAborted(move_base_msgs::MoveBaseResult(),
"Aborting because a transformation could not be found");
226 ROS_INFO(
"In idle mode, new goal accepted");
249 ROS_INFO(
"New goal received, updating movement");
251 move_base_msgs::MoveBaseGoal new_goal = * as_.
acceptNewGoal();
257 ROS_INFO(
"Preempt requested, aborting movement");
270 as_.
setSucceeded(move_base_msgs::MoveBaseResult(),
"Goal reached.");
276 ROS_INFO(
"Goal not active anymore. Stop!");
284 as_.
setAborted(move_base_msgs::MoveBaseResult(),
"Aborting on the goal because the node has been killed");
289 void odometryCB(
const nav_msgs::Odometry::ConstPtr &odometry){
290 geometry_msgs::Vector3Stamped vec_stamped;
292 vec_stamped.vector = odometry->twist.twist.linear;
301 vec_stamped.vector = odometry->twist.twist.angular;
311 bool serviceCB(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
315 private_nh.
setParam(
"global_frame", req.data);
353 double getDistance2d(geometry_msgs::PoseStamped a, geometry_msgs::PoseStamped b);
354 double getDistance2d(geometry_msgs::Point a, geometry_msgs::Point b);
356 double sign(
double x);
359 bool goalValid(
const geometry_msgs::PoseStamped& goal_pose);
379 geometry_msgs::PoseStamped goal_global_;
380 if(goal_pose.header.frame_id ==
global_frame_)
return goal_pose;
407 return sqrt( pow(a.pose.position.x - b.pose.position.x,2) + pow(a.pose.position.y - b.pose.position.y,2) );
411 return sqrt( pow(a.x - b.x,2) + pow(a.y - b.y,2) );
415 if(x >= 0.0
f)
return 1.0f;
425 geometry_msgs::Vector3Stamped cmd_global, cmd_robot;
426 geometry_msgs::Twist msg;
430 cmd_global.vector.x = vx;
431 cmd_global.vector.y = vy;
438 cmd_robot.vector.x = 0.0f;
439 cmd_robot.vector.y = 0.0f;
445 if ( std::isnan(cmd_robot.vector.x) || std::isnan(cmd_robot.vector.y) || std::isnan(theta) )
447 std::string err =
"linear_nav: Output velocity contains NaN!";
450 if ( ! ( fabs(cmd_robot.vector.x) < 5.0 && fabs(cmd_robot.vector.y) < 5.0 && fabs(theta) < M_PI ) )
452 std::string err =
"linear_nav: Output velocity too high (x="+std::to_string(cmd_robot.vector.x)+
" y="+std::to_string(cmd_robot.vector.y)+
" theta="+std::to_string(theta)+
")";
456 catch ( std::string err )
464 msg.linear = cmd_robot.vector;
465 msg.angular.z = theta;
466 msg.linear.z = 0.0; msg.angular.x = 0.0; msg.angular.y = 0.0;
499 if( goal_pose.pose.orientation.x == 0.0 &&
500 goal_pose.pose.orientation.y == 0.0 &&
501 goal_pose.pose.orientation.z == 0.0 &&
502 goal_pose.pose.orientation.w == 0.0 )
504 ROS_WARN(
"Goal invalid! Received Quaternion with all values 0.0!");
510 << goal_pose.header.frame_id <<
" into global frame /" <<
global_frame_);
516 << goal_pose.header.frame_id <<
" into robot frame /" <<
robot_frame_);
530 double F_x, F_y, F_theta;
531 double distance_to_goal;
532 double theta, theta_goal;
533 double cmd_vx, cmd_vy, cmd_vtheta;
534 double vx_d, vy_d, vtheta_d, v_factor;
535 double v_max_goal =
v_max_;
540 pthread_mutex_unlock(&
m_mutex);
562 pthread_mutex_unlock(&
m_mutex);
571 as_.
setAborted(move_base_msgs::MoveBaseResult(),
"Cancel the goal because an obstacle is blocking the path.");
577 ROS_INFO(
"Cancel the goal because an obstacle is blocking the path.");
578 pthread_mutex_unlock(&
m_mutex);
590 v_max_goal = distance_to_goal * goal_linear_slope;
593 else if(v_max_goal < 0.0
f) v_max_goal = 0.0f;
600 v_factor = v_max_goal / sqrt(vy_d*vy_d + vx_d*vx_d);
602 if(v_factor > 1.0) v_factor = 1.0;
614 if(v_factor > 1.0) v_factor = 1.0;
629 pthread_mutex_unlock(&
m_mutex);
637 int main(
int argc,
char** argv)
652 while(nodeClass.
nh_.
ok())
geometry_msgs::PoseStamped transformGoalToMap(geometry_msgs::PoseStamped goal_pose)
bool goalValid(const geometry_msgs::PoseStamped &goal_pose)
boost::shared_ptr< const Goal > acceptNewGoal()
double goal_abortion_speed_rot_
geometry_msgs::Vector3Stamped robot_twist_angular_robot_
#define ROS_DEBUG_STREAM_NAMED(name, args)
void publish(const boost::shared_ptr< M > &message) const
double getThetaDiffRad(double target, double actual)
double slow_down_distance_
void actionCB(const move_base_msgs::MoveBaseGoalConstPtr &goal)
static double getYaw(const Quaternion &bt_q)
bool getUseMoveAction(void)
void topicCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > * action_client_
geometry_msgs::Vector3Stamped robot_twist_linear_robot_
geometry_msgs::PoseStamped getRobotPoseGlobal()
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > as_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::Subscriber goal_sub_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
double getDistance2d(geometry_msgs::PoseStamped a, geometry_msgs::PoseStamped b)
ROSCPP_DECL void spin(Spinner &spinner)
std::string robot_footprint_frame_
double goal_abortion_time_
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool isPreemptRequested()
geometry_msgs::PoseStamped zero_pose_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
void publishVelocitiesGlobal(double vx, double vy, double theta)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
move_base_msgs::MoveBaseResult result_
#define ROS_INFO_STREAM(args)
geometry_msgs::PoseStamped goal_pose_global_
bool notMovingDueToObstacle()
void performControllerStep()
double goal_abortion_speed_
bool serviceCB(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
tf::TransformListener tf_listener_
bool hasParam(const std::string &key) const
int main(int argc, char **argv)
ros::Subscriber odometry_sub_
ROSCPP_DECL void spinOnce()
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
ros::Publisher topic_pub_command_
NodeClass(std::string name)
bool isNewGoalAvailable()
double speed_threshold_rot_
def shortest_angular_distance(from_angle, to_angle)
void odometryCB(const nav_msgs::Odometry::ConstPtr &odometry)
geometry_msgs::PoseStamped robot_pose_global_
double goal_threshold_rot_
std::string global_frame_