41 "pose_base_controller",
81 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
82 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
83 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
84 ROS_DEBUG(
"In the odometry callback with velocity values: (%.2f, %.2f, %.2f)",
90 double v1_x = x - pt_x;
91 double v1_y = y - pt_y;
92 double v2_x = cos(heading);
93 double v2_y = sin(heading);
95 double perp_dot = v1_x * v2_y - v1_y * v2_x;
96 double dot = v1_x * v2_x + v1_y * v2_y;
99 double vector_angle = atan2(perp_dot, dot);
101 return -1.0 * vector_angle;
106 global_pose.setIdentity();
107 robot_pose.setIdentity();
128 ROS_WARN(
"Failed to transform the goal pose from %s into the %s frame: %s",
133 move_base_msgs::MoveBaseGoal fixed_goal;
140 bool success =
false;
151 geometry_msgs::Twist empty_twist;
168 nav_msgs::Odometry base_odom;
200 ROS_WARN(
"The %s frame to %s frame transform is more than %.2f seconds old, will not move",
202 geometry_msgs::Twist empty_twist;
208 ROS_ERROR(
"Can't transform: %s\n", ex.what());
209 geometry_msgs::Twist empty_twist;
213 ROS_DEBUG(
"PoseBaseController: current robot pose %f %f ==> %f", robot_pose.getOrigin().x(), robot_pose.getOrigin().y(),
tf::getYaw(robot_pose.getRotation()));
214 ROS_DEBUG(
"PoseBaseController: target robot pose %f %f ==> %f", target_pose.getOrigin().x(), target_pose.getOrigin().y(),
tf::getYaw(target_pose.getRotation()));
217 geometry_msgs::Twist diff =
diff2D(target_pose, robot_pose);
218 ROS_DEBUG(
"PoseBaseController: diff %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z);
229 geometry_msgs::Twist empty_twist;
241 geometry_msgs::Twist res;
262 if(fabs(neg_yaw_diff) < fabs(yaw_diff)){
263 ROS_DEBUG(
"Negative is better: %.2f", neg_yaw_diff);
264 yaw_diff = neg_yaw_diff;
273 diff = pose2.
inverse() * new_pose;
283 geometry_msgs::Twist res = twist;
292 double lin_overshoot = sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) /
max_vel_lin_;
293 if (lin_overshoot > 1.0)
295 res.linear.x /= lin_overshoot;
296 res.linear.y /= lin_overshoot;
305 ROS_DEBUG(
"Angular command %f", res.angular.z);
310 int main(
int argc,
char** argv)
312 ros::init(argc, argv,
"pose_base_controller");
MoveBaseActionServer action_server_
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())
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
static double getYaw(const Quaternion &bt_q)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
double transform_tolerance_
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
double tolerance_timeout_
geometry_msgs::Twist diff2D(const tf::Pose &pose1, const tf::Pose &pose2)
ROSCPP_DECL void spin(Spinner &spinner)
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
void execute(const move_base_msgs::MoveBaseGoalConstPtr &user_goal)
TFSIMD_FORCE_INLINE const tfScalar & x() const
double rot_stopped_velocity_
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
static Quaternion createQuaternionFromYaw(double yaw)
double in_place_trans_vel_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
bool controlLoop(const move_base_msgs::MoveBaseGoal ¤t_goal)
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
bool isPreemptRequested()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf::Stamped< tf::Pose > getRobotPose()
tf::TransformListener tf_
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
int main(int argc, char **argv)
ros::Subscriber odom_sub_
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
double min_in_place_vel_th_
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
nav_msgs::Odometry base_odom_
move_base_msgs::MoveBaseGoal goalToFixedFrame(const move_base_msgs::MoveBaseGoal &goal)
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
double trans_stopped_velocity_