Robot.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_rbdyn/RobotData.h>
8 #include <mc_rbdyn/RobotFrame.h>
9 #include <mc_rbdyn/RobotModule.h>
10 #include <mc_rbdyn/Surface.h>
11 
13 
14 #include <mc_tvm/fwd.h>
15 
16 #include <RBDyn/MultiBody.h>
17 #include <RBDyn/MultiBodyConfig.h>
18 #include <RBDyn/MultiBodyGraph.h>
19 
20 #include <memory>
21 #include <optional>
22 #include <unordered_map>
23 
24 namespace mc_rbdyn
25 {
26 
27 struct Robots;
28 
29 struct Robot;
30 
33 {
34  friend struct Robot;
35 
36 private:
38  std::optional<sva::PTransformd> base_tf_ = std::nullopt;
40  std::optional<std::string> base_ = std::nullopt;
42  bool warn_on_missing_files_ = false;
44  RobotDataPtr data_ = nullptr;
45 
46 public:
47 #define MAKE_LOAD_ROBOT_PARAMETER_SETTER(T, NAME) \
48  inline LoadRobotParameters & NAME(T value) noexcept \
49  { \
50  NAME##_ = value; \
51  return *this; \
52  }
53 
54  MAKE_LOAD_ROBOT_PARAMETER_SETTER(const sva::PTransformd &, base_tf)
55  MAKE_LOAD_ROBOT_PARAMETER_SETTER(std::string_view, base)
56  MAKE_LOAD_ROBOT_PARAMETER_SETTER(bool, warn_on_missing_files)
58 
59 #undef MAKE_LOAD_ROBOT_PARAMETER_SETTER
60 };
61 
63 {
64  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
65  friend struct Robots;
66 
67 public:
68  using convex_pair_t = std::pair<std::string, S_ObjectPtr>;
69 
70 public:
71  Robot(Robot &&);
72  Robot & operator=(Robot &&);
73 
74  ~Robot();
75 
81  const std::string & name() const;
82 
84  const RobotModule & module() const;
85 
94  inline const BodySensor & bodySensor() const noexcept { return data_->bodySensors[0]; }
95 
100  void addBodySensor(const BodySensor & sensor);
101 
107  inline bool hasBodySensor(const std::string & name) const noexcept
108  {
109  return data_->bodySensorsIndex.count(name) != 0;
110  }
111 
117  inline bool bodyHasBodySensor(const std::string & body) const noexcept
118  {
119  return data_->bodyBodySensors.count(body) != 0;
120  }
121 
129  const BodySensor & bodySensor(const std::string & name) const;
130 
138  const BodySensor & bodyBodySensor(const std::string & name) const;
139 
141  inline const BodySensorVector & bodySensors() const noexcept { return data_->bodySensors; }
142 
144  /* End of Body sensors group */
145 
151  inline bool jointHasJointSensor(const std::string & joint) const noexcept
152  {
153  return data()->jointJointSensors.count(joint) != 0;
154  }
155 
163  const JointSensor & jointJointSensor(const std::string & joint) const;
164 
166  inline const std::vector<JointSensor> & jointSensors() const noexcept { return data_->jointSensors; }
167 
169  /* End of Joint sensors group */
170 
172  bool hasJoint(const std::string & name) const;
173 
175  bool hasBody(const std::string & name) const;
176 
178  inline bool hasFrame(const std::string & name) const noexcept { return frames_.count(name) != 0; }
179 
184  inline const RobotFrame & frame(const std::string & name) const
185  {
186  auto it = frames_.find(name);
187  if(it != frames_.end()) { return *it->second; }
188  mc_rtc::log::error_and_throw("No frame named {} in {}", name, name_);
189  }
190 
195  inline RobotFrame & frame(const std::string & name)
196  {
197  return const_cast<RobotFrame &>(static_cast<const Robot *>(this)->frame(name));
198  }
199 
201  std::vector<std::string> frames() const;
202 
217  RobotFrame & makeFrame(const std::string & name, RobotFrame & parent, sva::PTransformd X_p_f, bool baked = false);
218 
237  RobotFramePtr makeTemporaryFrame(const std::string & name,
238  const RobotFrame & parent,
239  sva::PTransformd X_p_f,
240  bool baked = false) const;
241 
249  void makeFrames(std::vector<mc_rbdyn::RobotModule::FrameDescription> frames);
250 
255  unsigned int jointIndexByName(const std::string & name) const;
256 
269  int jointIndexInMBC(size_t jointIndex) const;
270 
275  unsigned int bodyIndexByName(const std::string & name) const;
276 
278  rbd::MultiBody & mb();
280  const rbd::MultiBody & mb() const;
281 
283  rbd::MultiBodyConfig & mbc();
285  const rbd::MultiBodyConfig & mbc() const;
286 
288  rbd::MultiBodyGraph & mbg();
290  const rbd::MultiBodyGraph & mbg() const;
291 
293  const std::vector<std::vector<double>> & q() const;
295  const std::vector<std::vector<double>> & alpha() const;
297  const std::vector<std::vector<double>> & alphaD() const;
299  const std::vector<std::vector<double>> & jointTorque() const;
301  inline const std::vector<std::vector<double>> & controlTorque() const noexcept { return jointTorque(); }
303  const std::vector<sva::PTransformd> & bodyPosW() const;
305  const std::vector<sva::MotionVecd> & bodyVelW() const;
307  const std::vector<sva::MotionVecd> & bodyVelB() const;
309  const std::vector<sva::MotionVecd> & bodyAccB() const;
311  std::vector<std::vector<double>> & q();
313  std::vector<std::vector<double>> & alpha();
315  std::vector<std::vector<double>> & alphaD();
317  std::vector<std::vector<double>> & jointTorque();
319  inline std::vector<std::vector<double>> & controlTorque() noexcept { return jointTorque(); }
321  std::vector<sva::PTransformd> & bodyPosW();
323  std::vector<sva::MotionVecd> & bodyVelW();
325  std::vector<sva::MotionVecd> & bodyVelB();
327  std::vector<sva::MotionVecd> & bodyAccB();
328 
333  const sva::PTransformd & bodyPosW(const std::string & name) const;
334 
341  sva::PTransformd X_b1_b2(const std::string & b1, const std::string & b2) const;
342 
347  const sva::MotionVecd & bodyVelW(const std::string & name) const;
348 
353  const sva::MotionVecd & bodyVelB(const std::string & name) const;
354 
359  const sva::MotionVecd & bodyAccB(const std::string & name) const;
360 
362  Eigen::Vector3d com() const;
364  Eigen::Vector3d comVelocity() const;
366  Eigen::Vector3d comAcceleration() const;
367 
381  sva::ForceVecd surfaceWrench(const std::string & surfaceName) const;
382 
396  sva::ForceVecd bodyWrench(const std::string & bodyName) const;
397 
409  Eigen::Vector2d cop(const std::string & frame, double min_pressure = 0.5) const;
410 
422  Eigen::Vector3d copW(const std::string & frame, double min_pressure = 0.5) const;
423 
431  sva::ForceVecd netWrench(const std::vector<std::string> & sensorNames) const;
432 
453  Eigen::Vector3d zmp(const sva::ForceVecd & netTotalWrench,
454  const Eigen::Vector3d & plane_p,
455  const Eigen::Vector3d & plane_n,
456  double minimalNetNormalForce = 1.) const;
457 
473  bool zmp(Eigen::Vector3d & zmpOut,
474  const sva::ForceVecd & netTotalWrench,
475  const Eigen::Vector3d & plane_p,
476  const Eigen::Vector3d & plane_n,
477  double minimalNetNormalForce = 1.) const noexcept;
478 
494  Eigen::Vector3d zmp(const sva::ForceVecd & netTotalWrench,
495  const sva::PTransformd & zmpFrame,
496  double minimalNetNormalForce = 1.) const;
497 
514  bool zmp(Eigen::Vector3d & zmpOut,
515  const sva::ForceVecd & netTotalWrench,
516  const sva::PTransformd & zmpFrame,
517  double minimalNetNormalForce = 1.) const noexcept;
518 
525  Eigen::Vector3d zmp(const std::vector<std::string> & sensorNames,
526  const Eigen::Vector3d & plane_p,
527  const Eigen::Vector3d & plane_n,
528  double minimalNetNormalForce = 1.) const;
529 
536  bool zmp(Eigen::Vector3d & zmpOut,
537  const std::vector<std::string> & sensorNames,
538  const Eigen::Vector3d & plane_p,
539  const Eigen::Vector3d & plane_n,
540  double minimalNetNormalForce = 1.) const noexcept;
541 
549  Eigen::Vector3d zmp(const std::vector<std::string> & sensorNames,
550  const sva::PTransformd & zmpFrame,
551  double minimalNetNormalForce = 1.) const;
552 
560  bool zmp(Eigen::Vector3d & zmpOut,
561  const std::vector<std::string> & sensorNames,
562  const sva::PTransformd & zmpFrame,
563  double minimalNetNormalForce = 1.) const noexcept;
564 
566  const std::vector<std::vector<double>> & ql() const;
568  const std::vector<std::vector<double>> & qu() const;
570  const std::vector<std::vector<double>> & vl() const;
572  const std::vector<std::vector<double>> & vu() const;
574  const std::vector<std::vector<double>> & al() const;
576  const std::vector<std::vector<double>> & au() const;
578  const std::vector<std::vector<double>> & jl() const;
580  const std::vector<std::vector<double>> & ju() const;
582  const std::vector<std::vector<double>> & tl() const;
584  const std::vector<std::vector<double>> & tu() const;
586  const std::vector<std::vector<double>> & tdl() const;
588  const std::vector<std::vector<double>> & tdu() const;
590  std::vector<std::vector<double>> & ql();
592  std::vector<std::vector<double>> & qu();
594  std::vector<std::vector<double>> & vl();
596  std::vector<std::vector<double>> & vu();
598  std::vector<std::vector<double>> & al();
600  std::vector<std::vector<double>> & au();
602  std::vector<std::vector<double>> & jl();
604  std::vector<std::vector<double>> & ju();
606  std::vector<std::vector<double>> & tl();
608  std::vector<std::vector<double>> & tu();
610  std::vector<std::vector<double>> & tdl();
612  std::vector<std::vector<double>> & tdu();
613 
615  const std::vector<Flexibility> & flexibility() const;
617  std::vector<Flexibility> & flexibility();
618 
626  void zmpTarget(const Eigen::Vector3d & zmp);
627 
632  const Eigen::Vector3d & zmpTarget() const;
633 
635  inline double mass() const noexcept { return mass_; }
636 
645  inline const std::vector<double> & encoderValues() const noexcept { return data_->encoderValues; }
646 
648  inline const std::vector<double> & encoderVelocities() const noexcept { return data_->encoderVelocities; }
649 
651  inline const std::vector<double> & jointTorques() const noexcept { return data_->jointTorques; }
652 
654  inline const std::vector<std::string> & refJointOrder() const { return data_->refJointOrder; }
655 
657  /* End Joints sensors section */
658 
677  void addForceSensor(const mc_rbdyn::ForceSensor & fs);
678 
685  inline bool hasForceSensor(const std::string & name) const noexcept
686  {
687  return data_->forceSensorsIndex.count(name) != 0;
688  }
689 
700  inline bool bodyHasForceSensor(const std::string & body) const noexcept
701  {
702  return data_->bodyForceSensors_.count(body) != 0;
703  }
704 
718  inline bool surfaceHasForceSensor(const std::string & surface) const
719  {
720  return bodyHasForceSensor(this->surface(surface).bodyName());
721  }
722 
732  inline bool bodyHasIndirectForceSensor(const std::string & body) const
733  {
734  return bodyHasForceSensor(body) || findIndirectForceSensorBodyName(body).empty();
735  }
736 
745  inline bool surfaceHasIndirectForceSensor(const std::string & surface) const
746  {
747  return bodyHasIndirectForceSensor(this->surface(surface).bodyName());
748  }
749 
759  const ForceSensor & forceSensor(const std::string & name) const;
760 
772  const ForceSensor & bodyForceSensor(const std::string & body) const;
773 
778  const ForceSensor * findBodyForceSensor(const std::string & body) const;
779 
791  const ForceSensor & surfaceForceSensor(const std::string & surfaceName) const;
792 
803  const ForceSensor & indirectBodyForceSensor(const std::string & body) const;
804 
817  const ForceSensor & indirectSurfaceForceSensor(const std::string & surface) const;
818 
820  inline const std::vector<ForceSensor> & forceSensors() const noexcept { return data_->forceSensors; }
821 
823  /* End of Force sensors group */
824 
839  template<typename T>
840  bool hasDevice(const std::string & name) const noexcept;
841 
843  template<typename T>
844  inline bool hasSensor(const std::string & name) const noexcept
845  {
846  return hasDevice<T>(name);
847  }
848 
860  template<typename T>
861  const T & device(const std::string & name) const;
862 
864  template<typename T>
865  T & device(const std::string & name)
866  {
867  return const_cast<T &>(const_cast<const Robot *>(this)->device<T>(name));
868  }
869 
871  inline const DevicePtrVector & devices() const noexcept { return data_->devices; }
872 
874  template<typename T>
875  inline const T & sensor(const std::string & name) const
876  {
877  return device<T>(name);
878  }
879 
881  template<typename T>
882  inline T & sensor(const std::string & name)
883  {
884  return device<T>(name);
885  }
886 
888  void addDevice(DevicePtr device);
889 
891  inline void addSensor(SensorPtr sensor) { addDevice(std::move(sensor)); }
892 
894  /* End of Devices group */
895 
900  bool hasSurface(const std::string & surface) const;
901 
903  mc_rbdyn::Surface & surface(const std::string & sName);
905  const mc_rbdyn::Surface & surface(const std::string & sName) const;
906 
912  sva::PTransformd surfacePose(const std::string & sName) const;
913 
915  mc_rbdyn::Surface & copySurface(const std::string & sName, const std::string & name);
916 
918  void addSurface(mc_rbdyn::SurfacePtr surface, bool doNotReplace = true);
919 
921  const std::map<std::string, mc_rbdyn::SurfacePtr> & surfaces() const;
922 
924  std::vector<std::string> availableSurfaces() const;
925 
930  bool hasConvex(const std::string & name) const;
931 
937  convex_pair_t & convex(const std::string & cName);
939  const convex_pair_t & convex(const std::string & cName) const;
940 
945  const std::map<std::string, convex_pair_t> & convexes() const;
946 
960  void addConvex(const std::string & name,
961  const std::string & body,
962  S_ObjectPtr convex,
963  const sva::PTransformd & X_b_c = sva::PTransformd::Identity());
964 
975  void removeConvex(const std::string & name);
976 
983  const sva::PTransformd & bodyTransform(const std::string & bName) const;
984 
986  const sva::PTransformd & bodyTransform(int bodyIndex) const;
987 
989  const std::vector<sva::PTransformd> & bodyTransforms() const;
990 
992  const sva::PTransformd & collisionTransform(const std::string & cName) const;
993 
995  void loadRSDFFromDir(const std::string & surfaceDir);
996 
998  std::map<std::string, std::vector<double>> stance() const;
999 
1001  inline mc_rbdyn::Robots & robots() noexcept { return *robots_; }
1002 
1004  inline const mc_rbdyn::Robots & robots() const noexcept { return *robots_; }
1005 
1007  unsigned int robotIndex() const;
1008 
1010  void forwardKinematics();
1012  void forwardKinematics(rbd::MultiBodyConfig & mbc) const;
1013 
1015  void forwardVelocity();
1017  void forwardVelocity(rbd::MultiBodyConfig & mbc) const;
1018 
1020  void forwardAcceleration(const sva::MotionVecd & A_0 = sva::MotionVecd(Eigen::Vector6d::Zero()));
1022  void forwardAcceleration(rbd::MultiBodyConfig & mbc,
1023  const sva::MotionVecd & A_0 = sva::MotionVecd(Eigen::Vector6d::Zero())) const;
1024 
1026  void eulerIntegration(double step);
1028  void eulerIntegration(rbd::MultiBodyConfig & mbc, double step) const;
1029 
1031  const sva::PTransformd & posW() const;
1043  void posW(const sva::PTransformd & pt);
1044 
1051  void velW(const sva::MotionVecd & vel);
1052 
1054  const sva::MotionVecd & velW() const;
1055 
1062  void accW(const sva::MotionVecd & acc);
1063 
1067  const sva::MotionVecd accW() const;
1068 
1075  mc_control::Gripper & gripper(const std::string & gripper);
1076 
1083  const mc_control::Gripper & gripper(const std::string & gripper) const;
1084 
1086  bool hasGripper(const std::string & gripper) const;
1087 
1088  inline const std::unordered_map<std::string, mc_control::GripperPtr> & grippersByName() const noexcept
1089  {
1090  return data_->grippers;
1091  }
1092 
1094  inline const std::vector<mc_control::GripperRef> & grippers() const noexcept { return data_->grippersRef; }
1095 
1097  inline const RobotDataPtr data() const noexcept { return data_; }
1098 
1104  mc_tvm::Robot & tvmRobot() const;
1105 
1115  mc_tvm::Convex & tvmConvex(const std::string & name) const;
1116 
1117 private:
1118  Robots * robots_;
1119  unsigned int robots_idx_;
1120  std::string name_;
1121  Eigen::Vector3d zmp_;
1122  std::vector<sva::PTransformd> bodyTransforms_;
1123  std::vector<std::vector<double>> ql_;
1124  std::vector<std::vector<double>> qu_;
1125  std::vector<std::vector<double>> vl_;
1126  std::vector<std::vector<double>> vu_;
1127  std::vector<std::vector<double>> al_;
1128  std::vector<std::vector<double>> au_;
1129  std::vector<std::vector<double>> jl_;
1130  std::vector<std::vector<double>> ju_;
1131  std::vector<std::vector<double>> tl_;
1132  std::vector<std::vector<double>> tu_;
1133  std::vector<std::vector<double>> tdl_;
1134  std::vector<std::vector<double>> tdu_;
1135  std::map<std::string, convex_pair_t> convexes_;
1136  std::map<std::string, sva::PTransformd> collisionTransforms_;
1137  std::map<std::string, mc_rbdyn::SurfacePtr> surfaces_;
1138  std::map<std::string, std::vector<double>> stance_;
1140  RobotDataPtr data_;
1143  std::vector<int> refJointIndexToMBCIndex_;
1145  Springs springs_;
1147  std::vector<Flexibility> flexibility_;
1149  std::unordered_map<std::string, RobotFramePtr> frames_;
1151  double mass_ = 0.0;
1152 
1153 protected:
1155  {
1156  };
1157 
1158 public:
1166  const std::string & name,
1167  Robots & robots,
1168  unsigned int robots_idx,
1169  bool loadFiles,
1170  const LoadRobotParameters & params = {});
1171 
1172 protected:
1174  void copyLoadedData(Robot & destination) const;
1175 
1182  void fixSurfaces();
1183 
1191  void fixSurface(Surface & surface);
1192 
1194  void fixCollisionTransforms();
1195 
1204  std::string findIndirectForceSensorBodyName(const std::string & bodyName) const;
1205 
1206 private:
1207  Robot(const Robot &) = delete;
1208  Robot & operator=(const Robot &) = delete;
1209 
1210  /* mutable to allow initialization in const method */
1211  mutable mc_tvm::RobotPtr tvm_robot_;
1212 
1213  /* mutable to allow initialization in const method */
1214  mutable std::map<std::string, mc_tvm::ConvexPtr> tvm_convexes_;
1215 
1221  void name(const std::string & n);
1222 
1224  LoadRobotParameters load_params_;
1225 };
1226 
1261  const mc_rbdyn::Robots & robots,
1262  const std::string & prefix,
1263  bool required = false,
1264  const std::string & robotIndexKey = "robotIndex",
1265  const std::string & robotNameKey = "robot",
1266  const std::string & defaultRobotName = "");
1267 
1274 std::string MC_RBDYN_DLLAPI robotNameFromConfig(const mc_rtc::Configuration & config,
1275  const mc_rbdyn::Robots & robots,
1276  const std::string & prefix = "",
1277  bool required = false,
1278  const std::string & robotIndexKey = "robotIndex",
1279  const std::string & robotNameKey = "robot",
1280  const std::string & defaultRobotName = "");
1281 
1292 unsigned int MC_RBDYN_DLLAPI robotIndexFromConfig(const mc_rtc::Configuration & config,
1293  const mc_rbdyn::Robots & robots,
1294  const std::string & prefix = "",
1295  bool required = false,
1296  const std::string & robotIndexKey = "robotIndex",
1297  const std::string & robotNameKey = "robot",
1298  const std::string & defaultRobotName = "");
1299 
1302 /*FIXME Not implemetend for now, only used for ATLAS
1303 void loadPolyTorqueBoundsData(const std::string & file, Robot & robot);
1304 */
1305 
1306 } // namespace mc_rbdyn
1307 
1308 #include <mc_rbdyn/Robot.hpp>
mc_rtc::Configuration
Simplify access to values hold within a JSON file.
Definition: Configuration.h:165
mc_rbdyn::Robots
Definition: Robots.h:15
RobotFrame.h
mc_rbdyn::Robot::surfaceHasIndirectForceSensor
bool surfaceHasIndirectForceSensor(const std::string &surface) const
Definition: Robot.h:745
mc_rbdyn::zmp
Eigen::Vector3d MC_RBDYN_DLLAPI zmp(const sva::ForceVecd &netTotalWrench, const Eigen::Vector3d &plane_p, const Eigen::Vector3d &plane_n, double minimalNetNormalForce=1.)
Actual ZMP computation from net total wrench and the ZMP plane.
mc_rbdyn::Robot::jointSensors
const std::vector< JointSensor > & jointSensors() const noexcept
Definition: Robot.h:166
mc_rbdyn::Robot::surfaceHasForceSensor
bool surfaceHasForceSensor(const std::string &surface) const
Checks if the surface has a force sensor directly attached to it.
Definition: Robot.h:718
mc_rbdyn::Robot::forceSensors
const std::vector< ForceSensor > & forceSensors() const noexcept
Definition: Robot.h:820
mc_rbdyn::S_ObjectPtr
std::shared_ptr< sch::S_Object > S_ObjectPtr
Definition: RobotModule.h:35
mc_rbdyn::Robot::hasBodySensor
bool hasBodySensor(const std::string &name) const noexcept
Definition: Robot.h:107
mc_rbdyn::Robot::robots
const mc_rbdyn::Robots & robots() const noexcept
Definition: Robot.h:1004
mc_rbdyn::Robot::hasFrame
bool hasFrame(const std::string &name) const noexcept
Definition: Robot.h:178
mc_rbdyn::DevicePtrVector
Definition: RobotModule.h:41
mc_rbdyn::Robot::jointHasJointSensor
bool jointHasJointSensor(const std::string &joint) const noexcept
Definition: Robot.h:151
generic_gripper.h
mc_rbdyn::SurfacePtr
std::shared_ptr< Surface > SurfacePtr
Definition: Surface.h:72
mc_rbdyn::Robot
Definition: Robot.h:62
mc_rbdyn::Robot::hasSensor
bool hasSensor(const std::string &name) const noexcept
Definition: Robot.h:844
mc_rbdyn::Robot::controlTorque
std::vector< std::vector< double > > & controlTorque() noexcept
Definition: Robot.h:319
mc_rbdyn::Robot::convex_pair_t
std::pair< std::string, S_ObjectPtr > convex_pair_t
Definition: Robot.h:68
mc_rbdyn::Robot::encoderVelocities
const std::vector< double > & encoderVelocities() const noexcept
Definition: Robot.h:648
mc_tvm::Robot
Definition: Robot.h:48
mc_rbdyn::Springs
Definition: Springs.h:16
RobotModule.h
Surface.h
mc_rbdyn::Robot::bodyHasForceSensor
bool bodyHasForceSensor(const std::string &body) const noexcept
Definition: Robot.h:700
mc_rbdyn::ForceSensor
Definition: ForceSensor.h:19
mc_rbdyn::Robot::bodyHasBodySensor
bool bodyHasBodySensor(const std::string &body) const noexcept
Definition: Robot.h:117
mc_rbdyn::robotIndexFromConfig
unsigned int MC_RBDYN_DLLAPI robotIndexFromConfig(const mc_rtc::Configuration &config, const mc_rbdyn::Robots &robots, const std::string &prefix="", bool required=false, const std::string &robotIndexKey="robotIndex", const std::string &robotNameKey="robot", const std::string &defaultRobotName="")
Helper to obtain the robot index from configuration.
mc_rbdyn::SensorPtr
DevicePtr SensorPtr
Definition: Device.h:22
mc_rbdyn::RobotDataPtr
std::shared_ptr< RobotData > RobotDataPtr
Definition: RobotData.h:73
mc_rbdyn::Robot::NewRobotToken
Definition: Robot.h:1154
mc_rbdyn::Robot::hasForceSensor
bool hasForceSensor(const std::string &name) const noexcept
Definition: Robot.h:685
mc_rbdyn::robotFromConfig
const MC_RBDYN_DLLAPI mc_rbdyn::Robot & robotFromConfig(const mc_rtc::Configuration &config, const mc_rbdyn::Robots &robots, const std::string &prefix, bool required=false, const std::string &robotIndexKey="robotIndex", const std::string &robotNameKey="robot", const std::string &defaultRobotName="")
Obtains a reference to a loaded robot from configuration (using robotName or robotIndex)
mc_rbdyn::RobotFrame
Definition: RobotFrame.h:21
mc_rbdyn::RobotModule
Definition: RobotModule.h:69
mc_rbdyn::Robot::robots
mc_rbdyn::Robots & robots() noexcept
Definition: Robot.h:1001
mc_rbdyn::LoadRobotParameters
Definition: Robot.h:32
mc_tvm::RobotPtr
std::unique_ptr< Robot > RobotPtr
Definition: fwd.h:25
MAKE_LOAD_ROBOT_PARAMETER_SETTER
#define MAKE_LOAD_ROBOT_PARAMETER_SETTER(T, NAME)
Definition: Robot.h:47
mc_rbdyn::Robot::grippersByName
const std::unordered_map< std::string, mc_control::GripperPtr > & grippersByName() const noexcept
Definition: Robot.h:1088
fwd.h
mc_rbdyn::BodySensor
Definition: BodySensor.h:19
mc_rbdyn::Robot::device
T & device(const std::string &name)
Definition: Robot.h:865
mc_rbdyn::Robot::grippers
const std::vector< mc_control::GripperRef > & grippers() const noexcept
Definition: Robot.h:1094
mc_rtc::log::error_and_throw
void error_and_throw(Args &&... args)
Definition: logging.h:47
mc_rbdyn::Surface
Definition: Surface.h:24
MC_RBDYN_DLLAPI
#define MC_RBDYN_DLLAPI
Definition: api.h:50
mc_rbdyn::Robot::sensor
const T & sensor(const std::string &name) const
Definition: Robot.h:875
mc_rbdyn::RobotFramePtr
std::shared_ptr< RobotFrame > RobotFramePtr
Definition: fwd.h:24
mc_rbdyn::Robot::refJointOrder
const std::vector< std::string > & refJointOrder() const
Definition: Robot.h:654
mc_rbdyn::Robot::addSensor
void addSensor(SensorPtr sensor)
Definition: Robot.h:891
mc_rbdyn::Robot::sensor
T & sensor(const std::string &name)
Definition: Robot.h:882
mc_rbdyn::Robot::frame
const RobotFrame & frame(const std::string &name) const
Definition: Robot.h:184
mc_rbdyn::Robot::controlTorque
const std::vector< std::vector< double > > & controlTorque() const noexcept
Definition: Robot.h:301
mc_rbdyn::Robot::devices
const DevicePtrVector & devices() const noexcept
Definition: Robot.h:871
std
Definition: Contact.h:66
mc_rbdyn::BodySensorVector
std::vector< BodySensor, Eigen::aligned_allocator< BodySensor > > BodySensorVector
Definition: BodySensor.h:145
mc_rbdyn::DevicePtr
std::unique_ptr< Device > DevicePtr
Definition: Device.h:20
RobotData.h
mc_control::Gripper
A robot's gripper reprensentation.
Definition: generic_gripper.h:34
mc_rbdyn
Definition: generic_gripper.h:14
mc_rbdyn::Robot::bodyHasIndirectForceSensor
bool bodyHasIndirectForceSensor(const std::string &body) const
Definition: Robot.h:732
mc_rbdyn::Robot::jointTorques
const std::vector< double > & jointTorques() const noexcept
Definition: Robot.h:651
mc_rbdyn::Robot::data
const RobotDataPtr data() const noexcept
Definition: Robot.h:1097
mc_rtc::gui::Robot
auto Robot(const std::string &name, GetT get_fn)
Definition: Robot.h:56
mc_rbdyn::JointSensor
Definition: JointSensor.h:17
mc_rbdyn::Robot::frame
RobotFrame & frame(const std::string &name)
Definition: Robot.h:195
mc_rbdyn::Robot::bodySensors
const BodySensorVector & bodySensors() const noexcept
Definition: Robot.h:141
mc_rbdyn::Robot::bodySensor
const BodySensor & bodySensor() const noexcept
Definition: Robot.h:94
mc_rbdyn::robotNameFromConfig
std::string MC_RBDYN_DLLAPI robotNameFromConfig(const mc_rtc::Configuration &config, const mc_rbdyn::Robots &robots, const std::string &prefix="", bool required=false, const std::string &robotIndexKey="robotIndex", const std::string &robotNameKey="robot", const std::string &defaultRobotName="")
Helper to obtain the robot name from configuration.
mc_tvm::Convex
Definition: Convex.h:23
mc_rbdyn::Flexibility
Definition: Flexibility.h:24
mc_rbdyn::Robot::encoderValues
const std::vector< double > & encoderValues() const noexcept
Definition: Robot.h:645