robot_env_evaluator 1.0.1
Loading...
Searching...
No Matches
robot_env_evaluator.hpp
Go to the documentation of this file.
1
20#ifndef ROBOT_ENV_EVALUATOR_ROBOT_ENV_EVALUATOR_HPP
21#define ROBOT_ENV_EVALUATOR_ROBOT_ENV_EVALUATOR_HPP
22
23#include <pinocchio/multibody/model.hpp>
24#include <pinocchio/multibody/data.hpp>
25#include <pinocchio/multibody/geometry.hpp>
26
27#include <vector>
28#include <string>
29#include <variant>
30
31namespace robot_env_evaluator
32{
39 using Obstacle = std::variant<coal::Sphere>;
40
45 Obstacle obstacle;
46 Eigen::Matrix4d obstacle_pose;
47 };
48
53 int id;
54 double distance;
55 Eigen::Vector3d normal_vector;
56 Eigen::Vector3d nearest_point_on_robot;
57 Eigen::Vector3d nearest_point_on_object;
58 std::string contacted_robot_link;
59 Eigen::VectorXd projector_jointspace_to_dist;
60 Eigen::VectorXd projector_dist_to_jointspace;
61 };
62
83 public:
97 RobotEnvEvaluator(const pinocchio::Model& model,
98 const std::string& ee_name,
99 const std::vector<std::string>& joint_names,
100 const pinocchio::GeometryModel& collision_model,
101 const pinocchio::GeometryModel& visual_model = pinocchio::GeometryModel());
102
109
115
126 void forwardKinematics(const Eigen::VectorXd& q,
127 Eigen::Matrix4d& T,
128 const int joint_index = -1);
129
139 void forwardKinematicsByFrameName(const Eigen::VectorXd& q,
140 Eigen::Matrix4d& T,
141 const std::string& frame_name);
142
153 void jacobian(const Eigen::VectorXd& q,
154 Eigen::MatrixXd& J,
155 const int joint_index = -1);
156
164 void jacobianByFrameName(const Eigen::VectorXd& q,
165 Eigen::MatrixXd& J,
166 const std::string& frame_name);
167
175 void computeDistances(const Eigen::VectorXd& q,
176 const std::vector<obstacleInput>& obstacles,
177 std::vector<distanceResult>& distances);
178
179 // configurations
184 double robust_pinv_lambda_ = 0.001;
186
187 protected:
198 void jacobianFrame(const Eigen::VectorXd& q,
199 const double frame_index,
200 Eigen::MatrixXd& J);
201
210 void computeModelData(const Eigen::VectorXd& q);
211
212 // buffers
213 Eigen::VectorXd buffered_q_;
214
215 pinocchio::Model model_;
216 pinocchio::Data data_;
217 pinocchio::GeometryModel collision_model_;
218 pinocchio::GeometryModel visual_model_;
220 std::vector<double> joint_indices_;
221 };
222} // namespace robot_env_evaluator
223
224#endif // ROBOT_ENV_EVALUATOR_ROBOT_ENV_EVALUATOR_HPP
The main functionality class, which provides functionalities for evaluating robot environment informa...
void forwardKinematics(const Eigen::VectorXd &q, Eigen::Matrix4d &T, const int joint_index=-1)
The forward kinematics function for a specific joint, specified by the index.
double broad_phase_collision_padding_
The threshold for the broad phase search, this margin will be appended to first into GJK test and dis...
pinocchio::Data data_
The robot data, initialized from the model.
void jacobianFrame(const Eigen::VectorXd &q, const double frame_index, Eigen::MatrixXd &J)
Get the Jacobian of specific frame.
bool calculate_self_collision_
Whether to calculate self-collision in distance computation.
Eigen::VectorXd buffered_q_
The buffered joint configuration. This is used to avoid unnecessary computation.
void forwardKinematicsByFrameName(const Eigen::VectorXd &q, Eigen::Matrix4d &T, const std::string &frame_name)
The forward kinematics function for a specific frame, specified by the name.
void computeModelData(const Eigen::VectorXd &q)
Compute the model data from the joint configuration.
double robust_pinv_lambda_
The lambda value for the robust pseudo-inverse projector.
bool broad_phase_search_enable_
Whether to enable the broad phase search for collision detection.
pinocchio::GeometryModel visual_model_
The visual model.
bool projector_dist_to_control_with_zero_orientation_
Whether to use the full Jacobian and set the orientation to zero when calculating the projector.
bool projector_dist_to_control_enable_
Whether to calculate the projector from distance to control space.
~RobotEnvEvaluator()=default
Destroy the Robot Env Evaluator object.
void jacobianByFrameName(const Eigen::VectorXd &q, Eigen::MatrixXd &J, const std::string &frame_name)
Get the jacobian of specific frame, specified by the name.
int ee_index_
The internal index for end-effector.frame.
std::vector< double > joint_indices_
The joint indices for the robot model.
void computeDistances(const Eigen::VectorXd &q, const std::vector< obstacleInput > &obstacles, std::vector< distanceResult > &distances)
The distance computation function between the robot and obstacles.
pinocchio::GeometryModel collision_model_
The collision model.
void jacobian(const Eigen::VectorXd &q, Eigen::MatrixXd &J, const int joint_index=-1)
The jacobian function for a specific joint, specified by the index.
pinocchio::Model model_
The robot model.
std::variant< coal::Sphere > Obstacle
The Obstacle class, a variant of different coal primitive shapes.
Store the distance result between objects.
Store the obstacle and its pose in the world frame.