Exotica
distance_to_line_2d.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021, University of Oxford
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #ifndef EXOTICA_CORE_TASK_MAPS_DISTANCE_TO_LINE_H_
31 #define EXOTICA_CORE_TASK_MAPS_DISTANCE_TO_LINE_H_
32 
33 #include <exotica_core/task_map.h>
34 
35 #include <exotica_core_task_maps/distance_to_line_2d_initializer.h>
36 
37 #include <visualization_msgs/MarkerArray.h>
38 
39 namespace exotica
40 {
49 void PointToLineDistance(const Eigen::Vector2d& P1, const Eigen::Vector2d& P2, const Eigen::Vector2d& P3, double& d)
50 {
51  d = ((-P1.x() + P2.x()) * (P1.y() - P3.y()) - (P1.x() - P3.x()) * (-P1.y() + P2.y())) / (P2 - P1).norm();
52 }
53 
57 void PointToLineDistanceDerivative(const Eigen::Vector2d& P1,
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)
64 {
65  double squared_distance_between_P1_and_P2 = (P2 - P1).squaredNorm();
66 
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);
74 }
75 
76 class DistanceToLine2D : public TaskMap, public Instantiable<DistanceToLine2DInitializer>
77 {
78 public:
79  void AssignScene(ScenePtr scene) final;
82  // TODO: Hessian
83  int TaskSpaceDim() final;
84 
85 private:
86  void Initialize();
87  ros::Publisher pub_debug_;
88  visualization_msgs::MarkerArray debug_marker_array_msg_;
89 };
90 } // namespace exotica
91 
92 #endif // EXOTICA_CORE_TASK_MAPS_DISTANCE_TO_LINE_H_
exotica::DistanceToLine2D::AssignScene
void AssignScene(ScenePtr scene) final
exotica::DistanceToLine2D::pub_debug_
ros::Publisher pub_debug_
Definition: distance_to_line_2d.h:87
exotica::PointToLineDistance
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
exotica::TaskMap
Definition: task_map.h:52
exotica::Instantiable
Definition: property.h:110
exotica::DistanceToLine2D::Update
void Update(Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) final
exotica
Definition: cartpole_dynamics_solver.h:38
exotica::PointToLineDistanceDerivative
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
exotica::DistanceToLine2D::debug_marker_array_msg_
visualization_msgs::MarkerArray debug_marker_array_msg_
Definition: distance_to_line_2d.h:88
exotica::ScenePtr
std::shared_ptr< Scene > ScenePtr
Definition: scene.h:246
Eigen::VectorXdRef
Eigen::Ref< Eigen::VectorXd > VectorXdRef
Definition: conversions.h:54
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
Eigen::MatrixXdRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
exotica::DistanceToLine2D::Initialize
void Initialize()
exotica::DistanceToLine2D
Definition: distance_to_line_2d.h:76
exotica::DistanceToLine2D::TaskSpaceDim
int TaskSpaceDim() final
task_map.h