30 #ifndef PLANNER_CSPACE_PLANNER_3D_JUMP_DETECTOR_H 31 #define PLANNER_CSPACE_PLANNER_3D_JUMP_DETECTOR_H 61 , base_trans_prev_(
tf2::Quaternion(0, 0, 0, 1))
62 , map_trans_prev_(
tf2::Quaternion(0, 0, 0, 1))
68 map_frame_ = frame_id;
72 jump_detect_frame_ = frame_id;
85 geometry_msgs::TransformStamped base_trans_tmp =
87 geometry_msgs::TransformStamped map_trans_tmp =
97 map_trans.inverse() * map_trans_prev_ * (base_trans_prev_.
inverse() * base_trans);
98 base_trans_prev_ = base_trans;
99 map_trans_prev_ = map_trans;
107 const auto pos_diff =
diff.getOrigin().length();
110 if (pos_diff > pos_jump_ || fabs(yaw_diff) >
yaw_jump_)
112 ROS_ERROR(
"Position jumped (%0.3f/%0.3f, %0.3f/%0.3f); clearing history",
113 pos_diff, pos_jump_, yaw_diff, yaw_jump_);
120 #endif // PLANNER_CSPACE_PLANNER_3D_JUMP_DETECTOR_H
void setBaseFrame(const std::string &frame_id)
tf2_ros::TransformListener tfl_
tf2::Transform base_trans_prev_
tf2::Transform map_trans_prev_
std::string jump_detect_frame_
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 setMapFrame(const std::string &frame_id)
JumpDetector(tf2_ros::Buffer &tfbuf)
void fromMsg(const A &, B &b)
void setThresholds(const double pos_jump, const double yaw_jump)
double getYaw(const A &a)