Go to the documentation of this file.
32 const Eigen::Vector3d & frameVector,
34 double stiffness = 0.5,
35 double weight = 200.0);
57 unsigned int robotIndex,
58 const std::string & bodyName,
59 const Eigen::Vector3d & bodyVector,
60 unsigned int surfaceRobotIndex,
61 const std::string & surfaceName,
62 double stiffness = 0.5,
69 inline const sva::PTransformd &
offset() const noexcept {
return offset_; }
72 inline void offset(
const sva::PTransformd & off) noexcept { offset_ = off; }
80 sva::PTransformd offset_ = sva::PTransformd::Identity();
Simplify access to values hold within a JSON file.
Definition: Configuration.h:165
#define MC_TASKS_DLLAPI
Definition: api.h:50
Definition: QPSolver.h:85
Definition: RobotFrame.h:21
Orient a "gaze" vector defined on a body to look towards a world position. This task is a convenience...
Definition: LookAtTask.h:14
Definition: StabilizerStandingState.h:11
std::shared_ptr< const Frame > ConstFramePtr
Definition: fwd.h:29