30 #ifndef PLANNER_CSPACE_JUMP_DETECTOR_H 31 #define PLANNER_CSPACE_JUMP_DETECTOR_H 64 , base_trans_prev_(
tf2::Quaternion(0, 0, 0, 1))
65 , map_trans_prev_(
tf2::Quaternion(0, 0, 0, 1))
71 map_frame_ = frame_id;
75 jump_detect_frame_ = frame_id;
88 geometry_msgs::TransformStamped base_trans_tmp =
90 geometry_msgs::TransformStamped map_trans_tmp =
100 map_trans.inverse() * map_trans_prev_ * (base_trans_prev_.
inverse() * base_trans);
101 base_trans_prev_ = base_trans;
102 map_trans_prev_ = map_trans;
110 const auto pos_diff =
diff.getOrigin().length();
113 if (pos_diff > pos_jump_ || std::abs(yaw_diff) >
yaw_jump_)
115 ROS_ERROR(
"Position jumped (%0.3f/%0.3f, %0.3f/%0.3f); clearing history",
116 pos_diff, pos_jump_, yaw_diff, yaw_jump_);
125 #endif // PLANNER_CSPACE_JUMP_DETECTOR_H
tf2::Transform map_trans_prev_
tf2::Transform base_trans_prev_
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void setBaseFrame(const std::string &frame_id)
JumpDetector(tf2_ros::Buffer &tfbuf)
std::string jump_detect_frame_
void fromMsg(const A &, B &b)
void setMapFrame(const std::string &frame_id)
void setThresholds(const double pos_jump, const double yaw_jump)
double getYaw(const A &a)