Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_POINT_TO_LINE_H_
31 #define EXOTICA_CORE_TASK_MAPS_POINT_TO_LINE_H_
35 #include <exotica_core_task_maps/point_to_line_initializer.h>
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46 void Instantiate(
const PointToLineInitializer& init)
override;
59 Eigen::Vector3d
Direction(
const Eigen::Vector3d& point);
77 #endif // EXOTICA_CORE_TASK_MAPS_POINT_TO_LINE_H_
Eigen::Vector3d GetEndPoint()
Definition: task_map.h:52
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PointToLine()
Definition: property.h:110
Definition: cartpole_dynamics_solver.h:38
void Instantiate(const PointToLineInitializer &init) override
ros::Publisher pub_marker_
publish marker for RViz
Definition: point_to_line.h:70
Eigen::Vector3d line_start_
start point of line in base frame
Definition: point_to_line.h:61
std::string base_name_
frame of defined line
Definition: point_to_line.h:68
bool infinite_
Definition: point_to_line.h:64
Eigen::Ref< Eigen::VectorXd > VectorXdRef
Definition: conversions.h:54
Definition: point_to_line.h:39
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
int TaskSpaceDim() override
void SetEndPoint(const Eigen::Vector3d &point)
ros::Publisher pub_marker_label_
marker label
Definition: point_to_line.h:71
Eigen::Vector3d line_end_
end point of line in base frame
Definition: point_to_line.h:62
Eigen::Vector3d line_
vector from start to end point of line
Definition: point_to_line.h:63
std::string link_name_
frame of defined point
Definition: point_to_line.h:67
Eigen::Vector3d Direction(const Eigen::Vector3d &point)
direction computes the vector from a point to its projection on a line
bool visualize_
Definition: point_to_line.h:73