Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_SPHERE_COLLISION_H_
31 #define EXOTICA_CORE_TASK_MAPS_SPHERE_COLLISION_H_
35 #include <exotica_core_task_maps/sphere_collision_initializer.h>
36 #include <exotica_core_task_maps/sphere_initializer.h>
38 #include <visualization_msgs/Marker.h>
45 void Instantiate(
const SphereCollisionInitializer& init)
override;
51 double Distance(
const KDL::Frame& eff_A,
const KDL::Frame& eff_B,
double r_A,
double r_B);
52 void Jacobian(
const KDL::Frame& eff_A,
const KDL::Frame& eff_B,
const KDL::Jacobian& jacA,
const KDL::Jacobian& jacB,
double r_A,
double r_B, Eigen::Block<Eigen::Ref<Eigen::MatrixXd>, 1, -1,
false> ret);
54 std::map<std::string, std::vector<int>>
groups_;
64 #endif // EXOTICA_CORE_TASK_MAPS_SPHERE_COLLISION_H_
std::map< std::string, std::vector< int > > groups_
Definition: sphere_collision.h:54
Definition: task_map.h:52
ros::Publisher debug_pub_
Definition: sphere_collision.h:58
Definition: sphere_collision.h:42
Definition: property.h:110
Definition: cartpole_dynamics_solver.h:38
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
void Jacobian(const KDL::Frame &eff_A, const KDL::Frame &eff_B, const KDL::Jacobian &jacA, const KDL::Jacobian &jacB, double r_A, double r_B, Eigen::Block< Eigen::Ref< Eigen::MatrixXd >, 1, -1, false > ret)
visualization_msgs::MarkerArray debug_msg_
Definition: sphere_collision.h:57
double Distance(const KDL::Frame &eff_A, const KDL::Frame &eff_B, double r_A, double r_B)
double eps_
Definition: sphere_collision.h:59
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
int dim_
Definition: sphere_collision.h:60
std::vector< double > radiuses_
Definition: sphere_collision.h:55
void Instantiate(const SphereCollisionInitializer &init) override
int TaskSpaceDim() override