Avoids pointing end-effector at a given spherical object. More...
#include <avoid_look_at_sphere.h>
Private Member Functions | |
void | PublishObjectsAsMarkerArray () |
void | UpdateAsCostWithJacobian (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian) |
void | UpdateAsCostWithoutJacobian (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) |
void | UpdateAsInequalityConstraintWithJacobian (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian) |
void | UpdateAsInequalityConstraintWithoutJacobian (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) |
Private Attributes | |
Eigen::VectorXd | diameter_ |
The diameter of each object. More... | |
int | n_objects_ |
Number of spherical objects. More... | |
ros::Publisher | pub_markers_ |
publish marker for RViz More... | |
Eigen::VectorXd | radii_squared_ |
The square of each object radii. More... | |
void(AvoidLookAtSphere::* | UpdateTaskMapWithJacobian )(Eigen::VectorXdRefConst, Eigen::VectorXdRef, Eigen::MatrixXdRef) |
void(AvoidLookAtSphere::* | UpdateTaskMapWithoutJacobian )(Eigen::VectorXdRefConst, Eigen::VectorXdRef) |
Additional Inherited Members | |
Public Attributes inherited from exotica::TaskMap | |
int | id |
bool | is_used |
std::vector< KinematicSolution > | kinematics |
int | length |
int | length_jacobian |
int | start |
int | start_jacobian |
Public Attributes inherited from exotica::Object | |
bool | debug_ |
std::string | ns_ |
std::string | object_name_ |
Protected Attributes inherited from exotica::TaskMap | |
std::vector< KinematicFrameRequest > | frames_ |
ScenePtr | scene_ |
Protected Attributes inherited from exotica::Instantiable< AvoidLookAtSphereInitializer > | |
AvoidLookAtSphereInitializer | parameters_ |
Avoids pointing end-effector at a given spherical object.
This task map avoids pointing the end-effector a number of given spherical objects. AvoidLookAtSphere can be used as either a cost term or an inequality constraint. Each spherical object in the scene is defined by a position and radius . The position and radii of each object must be given.
When using AvoidLookAtSphere as a cost term, the forward mapping defining the task map is expressed by
for all where is the number of objects, is the orthogonal distance between the object center and the end-effector approach vector.
When using AvoidLookAtSphere as an inequality constraint, the forward mapping defining the task map is expressed by
for all .
Definition at line 62 of file avoid_look_at_sphere.h.
|
overridevirtual |
Reimplemented from exotica::Instantiable< AvoidLookAtSphereInitializer >.
Definition at line 131 of file avoid_look_at_sphere.cpp.
|
private |
Definition at line 88 of file avoid_look_at_sphere.cpp.
|
overridevirtual |
Implements exotica::TaskMap.
Definition at line 167 of file avoid_look_at_sphere.cpp.
|
overridevirtual |
Implements exotica::TaskMap.
Definition at line 119 of file avoid_look_at_sphere.cpp.
|
overridevirtual |
Reimplemented from exotica::TaskMap.
Definition at line 125 of file avoid_look_at_sphere.cpp.
|
private |
Definition at line 58 of file avoid_look_at_sphere.cpp.
|
private |
Definition at line 37 of file avoid_look_at_sphere.cpp.
|
private |
Definition at line 77 of file avoid_look_at_sphere.cpp.
|
private |
Definition at line 53 of file avoid_look_at_sphere.cpp.
|
private |
The diameter of each object.
Definition at line 81 of file avoid_look_at_sphere.h.
|
private |
Number of spherical objects.
Definition at line 80 of file avoid_look_at_sphere.h.
|
private |
publish marker for RViz
Definition at line 83 of file avoid_look_at_sphere.h.
|
private |
The square of each object radii.
Definition at line 82 of file avoid_look_at_sphere.h.
|
private |
Definition at line 79 of file avoid_look_at_sphere.h.
|
private |
Definition at line 78 of file avoid_look_at_sphere.h.