Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_AVOID_LOOK_AT_SPHERE_H_
31 #define EXOTICA_CORE_TASK_MAPS_AVOID_LOOK_AT_SPHERE_H_
35 #include <exotica_core_task_maps/avoid_look_at_sphere_initializer.h>
65 void Instantiate(
const AvoidLookAtSphereInitializer& init)
override;
87 #endif // EXOTICA_CORE_TASK_MAPS_AVOID_LOOK_AT_SPHERE_H_
Definition: task_map.h:52
Eigen::VectorXd diameter_
The diameter of each object.
Definition: avoid_look_at_sphere.h:81
void(AvoidLookAtSphere::* UpdateTaskMapWithoutJacobian)(Eigen::VectorXdRefConst, Eigen::VectorXdRef)
Definition: avoid_look_at_sphere.h:78
Definition: property.h:110
Definition: cartpole_dynamics_solver.h:38
void(AvoidLookAtSphere::* UpdateTaskMapWithJacobian)(Eigen::VectorXdRefConst, Eigen::VectorXdRef, Eigen::MatrixXdRef)
Definition: avoid_look_at_sphere.h:79
ros::Publisher pub_markers_
publish marker for RViz
Definition: avoid_look_at_sphere.h:83
void UpdateAsInequalityConstraintWithJacobian(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian)
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
Eigen::Ref< Eigen::VectorXd > VectorXdRef
Definition: conversions.h:54
int TaskSpaceDim() override
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
Eigen::VectorXd radii_squared_
The square of each object radii.
Definition: avoid_look_at_sphere.h:82
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
void Instantiate(const AvoidLookAtSphereInitializer &init) override
void PublishObjectsAsMarkerArray()
void UpdateAsCostWithJacobian(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian)
void UpdateAsInequalityConstraintWithoutJacobian(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi)
Avoids pointing end-effector at a given spherical object.
Definition: avoid_look_at_sphere.h:62
int n_objects_
Number of spherical objects.
Definition: avoid_look_at_sphere.h:80
void UpdateAsCostWithoutJacobian(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi)