mc_rtc  2.12.0
VectorOrientationTask.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 
8 
9 namespace mc_tasks
10 {
11 
14 {
26  const Eigen::Vector3d & frameVector,
27  double stiffness = 2.0,
28  double weight = 500.0);
29 
47  VectorOrientationTask(const std::string & bodyName,
48  const Eigen::Vector3d & bodyVector,
49  const Eigen::Vector3d & targetVector,
50  const mc_rbdyn::Robots & robots,
51  unsigned int robotIndex,
52  double stiffness = 2.0,
53  double weight = 500);
54 
56  VectorOrientationTask(const std::string & bodyName,
57  const Eigen::Vector3d & bodyVector,
58  const mc_rbdyn::Robots & robots,
59  unsigned int robotIndex,
60  double stiffness = 2.0,
61  double weight = 500);
62 
68  void reset() override;
69 
75  void targetVector(const Eigen::Vector3d & vector);
76 
82  Eigen::Vector3d targetVector() const;
83 
89  Eigen::Vector3d actual() const;
90 
92  std::string body() { return frame_->body(); }
93 
94  void load(mc_solver::QPSolver & solver, const mc_rtc::Configuration & config) override;
95 
96 protected:
97  void addToGUI(mc_rtc::gui::StateBuilder & gui) override;
98  void addToLogger(mc_rtc::Logger & logger) override;
99 
100 protected:
102 };
103 
104 } // namespace mc_tasks
#define MC_TASKS_DLLAPI
Definition: api.h:50
std::shared_ptr< const RobotFrame > ConstRobotFramePtr
Definition: fwd.h:25
Definition: StabilizerStandingState.h:12
Definition: RobotFrame.h:22
Definition: Robots.h:16
Simplify access to values hold within a JSON file.
Definition: Configuration.h:166
Logs controller data to disk.
Definition: Logger.h:30
Definition: StateBuilder.h:28
Definition: QPSolver.h:86
Generic wrapper for a trajectory dynamic over an error function.
Definition: TrajectoryTaskGeneric.h:27
Control the orientation of a vector attached to a frame.
Definition: VectorOrientationTask.h:14
mc_rbdyn::ConstRobotFramePtr frame_
Definition: VectorOrientationTask.h:101
VectorOrientationTask(const std::string &bodyName, const Eigen::Vector3d &bodyVector, const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=2.0, double weight=500)
Constructor with default target.
VectorOrientationTask(const mc_rbdyn::RobotFrame &frame, const Eigen::Vector3d &frameVector, double stiffness=2.0, double weight=500.0)
Constructor from a robot frame.
void targetVector(const Eigen::Vector3d &vector)
Set world target for the controlled vector.
Eigen::Vector3d targetVector() const
Get the target orientation.
std::string body()
Return the controlled body.
Definition: VectorOrientationTask.h:92
void load(mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override
Load parameters from a Configuration object.
void reset() override
Reset the task.
VectorOrientationTask(const std::string &bodyName, const Eigen::Vector3d &bodyVector, const Eigen::Vector3d &targetVector, const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=2.0, double weight=500)
Constructor with user-specified target.
void addToLogger(mc_rtc::Logger &logger) override
Eigen::Vector3d actual() const
Get the current body orientation.
void addToGUI(mc_rtc::gui::StateBuilder &gui) override