Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_DISTANCE_TO_LINE_H_
31 #define EXOTICA_CORE_TASK_MAPS_DISTANCE_TO_LINE_H_
35 #include <exotica_core_task_maps/distance_to_line_2d_initializer.h>
37 #include <visualization_msgs/MarkerArray.h>
49 void PointToLineDistance(
const Eigen::Vector2d& P1,
const Eigen::Vector2d& P2,
const Eigen::Vector2d& P3,
double& d)
51 d = ((-P1.x() + P2.x()) * (P1.y() - P3.y()) - (P1.x() - P3.x()) * (-P1.y() + P2.y())) / (P2 - P1).norm();
58 const Eigen::Vector2d& P2,
59 const Eigen::Vector2d& P3,
60 const Eigen::MatrixXd& dP1_dq,
61 const Eigen::MatrixXd& dP2_dq,
62 const Eigen::MatrixXd& dP3_dq,
63 Eigen::Ref<Eigen::MatrixXd>& derivative)
65 double squared_distance_between_P1_and_P2 = (P2 - P1).squaredNorm();
67 derivative = ((-P1.x() + P2.x()) * (P1.y() - P3.y()) - (P1.x() - P3.x()) * (-P1.y() + P2.y())) *
68 (-1.0 / 2.0 * (-P1.x() + P2.x()) * (-2 * dP1_dq.row(0) + 2 * dP2_dq.row(0)) -
69 1.0 / 2.0 * (-P1.y() + P2.y()) * (-2 * dP1_dq.row(1) + 2 * dP2_dq.row(1))) /
70 std::pow(squared_distance_between_P1_and_P2, 3.0 / 2.0) +
71 ((-P1.x() + P2.x()) * (dP1_dq.row(1) - dP3_dq.row(1)) + (P1.x() - P3.x()) * (dP1_dq.row(1) - dP2_dq.row(1)) +
72 (P1.y() - P2.y()) * (dP1_dq.row(0) - dP3_dq.row(0)) + (P1.y() - P3.y()) * (-dP1_dq.row(0) + dP2_dq.row(0))) /
73 std::sqrt(squared_distance_between_P1_and_P2);
92 #endif // EXOTICA_CORE_TASK_MAPS_DISTANCE_TO_LINE_H_
void AssignScene(ScenePtr scene) final
ros::Publisher pub_debug_
Definition: distance_to_line_2d.h:87
void PointToLineDistance(const Eigen::Vector2d &P1, const Eigen::Vector2d &P2, const Eigen::Vector2d &P3, double &d)
Computes the signed distance between a point and a line defined by two points in 2D.
Definition: distance_to_line_2d.h:49
Definition: task_map.h:52
Definition: property.h:110
void Update(Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) final
Definition: cartpole_dynamics_solver.h:38
void PointToLineDistanceDerivative(const Eigen::Vector2d &P1, const Eigen::Vector2d &P2, const Eigen::Vector2d &P3, const Eigen::MatrixXd &dP1_dq, const Eigen::MatrixXd &dP2_dq, const Eigen::MatrixXd &dP3_dq, Eigen::Ref< Eigen::MatrixXd > &derivative)
Derivative of signed distance between a point and a line defined by two points in 2D.
Definition: distance_to_line_2d.h:57
visualization_msgs::MarkerArray debug_marker_array_msg_
Definition: distance_to_line_2d.h:88
std::shared_ptr< Scene > ScenePtr
Definition: scene.h:246
Eigen::Ref< Eigen::VectorXd > VectorXdRef
Definition: conversions.h:54
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
Definition: distance_to_line_2d.h:76