LookAtFrameTask.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015-2022 CNRS-UM LIRMM, CNRS-AIST JRL
3  */
4 
5 #pragma once
6 
7 #include <mc_tasks/LookAtTask.h>
8 
9 namespace mc_tasks
10 {
11 
17 {
18 public:
32  const Eigen::Vector3d & frameVector,
33  const mc_rbdyn::Frame & target,
34  double stiffness = 0.5,
35  double weight = 200.0);
36 
56  LookAtFrameTask(const mc_rbdyn::Robots & robots,
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,
63  double weight = 200);
64 
66  void update(mc_solver::QPSolver &) override;
67 
69  inline const sva::PTransformd & offset() const noexcept { return offset_; }
70 
72  inline void offset(const sva::PTransformd & off) noexcept { offset_ = off; }
73 
74  void load(mc_solver::QPSolver & solver, const mc_rtc::Configuration & config) override;
75 
76 protected:
80  sva::PTransformd offset_ = sva::PTransformd::Identity();
81 };
82 
83 } // namespace mc_tasks
mc_rtc::Configuration
Simplify access to values hold within a JSON file.
Definition: Configuration.h:165
mc_rbdyn::Robots
Definition: Robots.h:15
mc_tasks::LookAtFrameTask::offset
const sva::PTransformd & offset() const noexcept
Access offset relative to the surface.
Definition: LookAtFrameTask.h:69
MC_TASKS_DLLAPI
#define MC_TASKS_DLLAPI
Definition: api.h:50
mc_solver::QPSolver
Definition: QPSolver.h:85
LookAtTask.h
mc_rbdyn::Frame
Definition: Frame.h:27
mc_tasks::LookAtFrameTask::offset
void offset(const sva::PTransformd &off) noexcept
Set the offset relative to the surface.
Definition: LookAtFrameTask.h:72
mc_rbdyn::RobotFrame
Definition: RobotFrame.h:21
mc_tasks::LookAtTask
Orient a "gaze" vector defined on a body to look towards a world position. This task is a convenience...
Definition: LookAtTask.h:14
mc_tasks::LookAtFrameTask::target_
mc_rbdyn::ConstFramePtr target_
Definition: LookAtFrameTask.h:78
mc_tasks::LookAtFrameTask
Track a frame position with a "gaze" vector. This task is a convenience wrapper for LookAtTask that t...
Definition: LookAtFrameTask.h:16
mc_tasks
Definition: StabilizerStandingState.h:11
mc_rbdyn::ConstFramePtr
std::shared_ptr< const Frame > ConstFramePtr
Definition: fwd.h:29