XBotInterface  2.4.1
XBotInterface provides a generic API to model and control a robot.
RobotInterface.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 IIT-ADVR
3  * Author: Arturo Laurenzi, Luca Muratore
4  * email: arturo.laurenzi@iit.it, luca.muratore@iit.it
5  *
6  * This program is free software: you can redistribute it and/or modify
7  * it under the terms of the GNU Lesser General Public License as published by
8  * the Free Software Foundation, either version 3 of the License, or
9  * (at your option) any later version.
10  *
11  * This program is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU Lesser General Public License for more details.
15  *
16  * You should have received a copy of the GNU Lesser General Public License
17  * along with this program. If not, see <http://www.gnu.org/licenses/>
18 */
19 
20 #ifndef __ROBOT_INTERFACE_H__
21 #define __ROBOT_INTERFACE_H__
22 
23 #include <vector>
24 #include <map>
25 #include <memory>
26 
27 #include <cstdlib>
28 
32 
33 namespace XBot
34 {
35 
37 {
38 
39 public:
40 
41  typedef std::shared_ptr<RobotInterface> Ptr;
42  typedef std::shared_ptr<const RobotInterface> ConstPtr;
43 
49  virtual ~RobotInterface() = default;
50 
51 
52  static void clearRobotMap(void);
53 
54 
62  static RobotInterface::Ptr getRobot(const ConfigOptions& config,
63  const std::string& robot_name = "");
64 
72  static RobotInterface::Ptr getRobot(const std::string& path_to_cfg,
73  const std::string& robot_name = "",
74  AnyMapConstPtr any_map = AnyMapConstPtr(),
75  const std::string& framework = "");
76 
83 
84  RobotInterface& operator=(const RobotInterface& other) = delete;
85  RobotInterface(const RobotInterface& other) = delete;
86 
93  virtual double getTime() const = 0;
94 
100  virtual bool isRunning() const = 0;
101 
111  bool sense(bool sync_model = true,
112  bool sync_references = false);
113 
119  bool move();
120 
127  RobotChain& operator()(const std::string& chain_name);
128  const RobotChain& operator()(const std::string& chain_name) const;
129 
136  RobotChain& chain(const std::string& chain_name);
137  const RobotChain& chain(const std::string& chain_name) const;
138 
145  RobotChain& arm(int arm_id);
146  const RobotChain& arm(int arm_id) const;
147 
154  RobotChain& leg(int leg_id);
155  const RobotChain& leg(int leg_id) const;
156 
181  template <typename... SyncFlags>
182  bool setReferenceFrom(const ModelInterface& model, SyncFlags... flags);
183 
184  // Control mode
185  bool setControlMode(const ControlMode& control_mode);
186  virtual bool setControlMode(const std::string& chain_name, const ControlMode& control_mode);
187  bool setControlMode(const std::map<std::string, ControlMode>& control_mode);
188  bool setControlMode(const std::map<int, ControlMode>& control_mode);
189 
190 
191  void getControlMode(std::map<std::string, ControlMode>& control_mode) const;
192  void getControlMode(std::map<int, ControlMode>& control_mode) const;
193 
194 
195  // Getters for RX
196 
203 
209  double getTimestampRx() const;
210 
211 
212  // Getters for TX
213 
219 
225  double getTimestampTx() const;
226 
227  // Setters for TX
228 
234 
235 
236 
237 protected:
238 
239  virtual bool post_init();
240 
241  virtual bool sense_internal(bool sync_references) = 0;
242  virtual bool read_sensors() = 0;
243  virtual bool sense_hands() = 0;
244 
245  virtual bool move_internal() = 0;
246  virtual bool move_hands() = 0;
247 
248  virtual bool init_robot(const ConfigOptions& config) = 0;
249  virtual bool set_control_mode_internal(int joint_id, const ControlMode& control_mode);
250 
251  // Setters for RX
252 
261  using XBotInterface::sync;
262 
264 
265 
266 private:
267 
268  virtual bool init_internal(const ConfigOptions& config);
269 
273  std::map<std::string, XBot::RobotChain::Ptr> _robot_chain_map;
274  XBot::RobotChain _dummy_chain;
275 
276 
277 
278  ModelInterface::Ptr _model;
279 
280  static std::map<std::string, RobotInterface::Ptr> _instance_ptr_map;
281 
282  std::vector<std::string> _model_ordered_chain_name;
283 
284  double _ts_rx;
285  double _ts_tx;
286 
287 
288 
289 };
290 
291 template <typename... SyncFlags>
293  SyncFlags... flags )
294 {
295  bool success = true;
296 
297  for (const auto & c : model._model_chain_map) {
298 
299  const std::string &chain_name = c.first;
300  const ModelChain &chain = *c.second;
301 
302  if(_robot_chain_map.count(chain_name))
303  {
304  _robot_chain_map.at(chain_name)->setReferenceFrom(chain, flags...);
305  }
306  }
307 
308  return success;
309 }
310 
311 }
312 
313 #endif // __ROBOT_INTERFACE_H__
XBot::XBotInterface::setDamping
bool setDamping(const Eigen::VectorXd &D)
Sets the XBotInterface internal joint damping according to the provided vector, which must be ordered...
Definition: XBotInterface.cpp:1008
XBot::ConfigOptions
Definition: ConfigOptions.h:36
XBot::XBotInterface::getJointEffort
bool getJointEffort(Eigen::VectorXd &tau) const
Gets the robot joint efforts as an Eigen vector.
Definition: XBotInterface.cpp:740
XBot::RobotInterface::isRunning
virtual bool isRunning() const =0
...
XBot::XBotInterface::getEffortReference
bool getEffortReference(Eigen::VectorXd &tau) const
Gets the robot effort references as an Eigen vector.
Definition: XBotInterface.cpp:751
XBot::XBotInterface::getMotorPosition
bool getMotorPosition(Eigen::VectorXd &q) const
Gets the robot motor positions as an Eigen vector.
Definition: XBotInterface.cpp:786
XBot::RobotInterface::operator()
RobotChain & operator()(const std::string &chain_name)
Getter for the robot chain with a certain chain_name.
Definition: RobotInterface.cpp:211
XBot::XBotInterface::getJointPosition
bool getJointPosition(Eigen::VectorXd &q) const
Gets the robot joint positions as an Eigen vector.
Definition: XBotInterface.cpp:348
XBot::RobotChain
Kinematic chain useful for a robot abstraction.
Definition: RobotChain.h:33
XBot::RobotInterface::getTimestampTx
double getTimestampTx() const
Get the TX timestamp: it corresponds to the last call to move()
Definition: RobotInterface.cpp:265
XBot::RobotInterface::sense_hands
virtual bool sense_hands()=0
XBot::ModelInterface::Ptr
std::shared_ptr< ModelInterface > Ptr
Shared pointer to a ModelInterface.
Definition: ModelInterface.h:56
XBot::XBotInterface::_chain_map
std::map< std::string, XBot::KinematicChain::Ptr > _chain_map
Definition: XBotInterface.h:1382
XBot::XBotInterface::getMotorVelocity
bool getMotorVelocity(Eigen::VectorXd &qdot) const
Gets the robot motor velocities as an Eigen vector.
Definition: XBotInterface.cpp:797
XBot::XBotInterface::setJointPosition
bool setJointPosition(const Eigen::VectorXd &q)
Sets the XBotInterface internal joint positions according to the provided vector, which must be order...
Definition: XBotInterface.cpp:1050
XBot::RobotInterface::RobotInterface
RobotInterface()
Default constructor.
Definition: RobotInterface.cpp:31
XBot::ControlMode
Definition: ControlMode.h:28
XBot::XBotInterface::getTemperature
bool getTemperature(Eigen::VectorXd &temp) const
Gets the robot joint temperatures as an Eigen vector.
Definition: XBotInterface.cpp:819
XBot::XBotInterface::_ordered_chain_names
std::vector< std::string > _ordered_chain_names
Definition: XBotInterface.h:1391
XBot::XBotInterface::setStiffness
bool setStiffness(const Eigen::VectorXd &K)
Sets the XBotInterface internal joint stiffness according to the provided vector, which must be order...
Definition: XBotInterface.cpp:1135
XBot::RobotInterface::set_control_mode_internal
virtual bool set_control_mode_internal(int joint_id, const ControlMode &control_mode)
Definition: RobotInterface.cpp:270
XBot::XBotInterface::setMotorPosition
bool setMotorPosition(const Eigen::VectorXd &q)
Sets the XBotInterface internal motor positions according to the provided vector, which must be order...
Definition: XBotInterface.cpp:1093
XBot::XBotInterface::sync
bool sync(const XBotInterface &other, SyncFlags... flags)
Synchronize the current XBotInterface with another XBotInterface object: only the common chains will ...
Definition: XBotInterface.h:1421
XBot::RobotInterface::ConstPtr
std::shared_ptr< const RobotInterface > ConstPtr
Definition: RobotInterface.h:42
XBot::RobotInterface::init_robot
virtual bool init_robot(const ConfigOptions &config)=0
XBot::RobotInterface::clearRobotMap
static void clearRobotMap(void)
Definition: RobotInterface.cpp:35
XBot::XBotInterface::getDamping
bool getDamping(Eigen::VectorXd &D) const
Gets the robot damping as an Eigen vector.
Definition: XBotInterface.cpp:729
XBot::RobotInterface::arm
RobotChain & arm(int arm_id)
Getter for the standard kinematic group arm: you can quickly access the i-th arm in the order specifi...
Definition: RobotInterface.cpp:191
XBot::XBotInterface::getVelocityReference
bool getVelocityReference(Eigen::VectorXd &qdot) const
Gets the robot velocity references as an Eigen vector.
Definition: XBotInterface.cpp:830
ModelInterface.h
XBot::XBotInterface::setJointVelocity
bool setJointVelocity(const Eigen::VectorXd &qdot)
Sets the XBotInterface internal joint velocities according to the provided vector,...
Definition: XBotInterface.cpp:1064
XBot::RobotInterface::operator=
RobotInterface & operator=(const RobotInterface &other)=delete
XBot::RobotInterface::move_hands
virtual bool move_hands()=0
XBot::RobotInterface::getRobot
static RobotInterface::Ptr getRobot(const ConfigOptions &config, const std::string &robot_name="")
...
Definition: RobotInterface.cpp:43
XBot::XBotInterface::getChainMap
const std::map< std::string, XBot::KinematicChain::Ptr > & getChainMap() const
Getter for the chain map inside the XBotInterface.
Definition: XBotInterface.cpp:1389
XBot::XBotInterface::setJointEffort
bool setJointEffort(const Eigen::VectorXd &tau)
Sets the XBotInterface internal joint efforts according to the provided vector, which must be ordered...
Definition: XBotInterface.cpp:1022
XBotInterface.h
XBot::RobotInterface::move
bool move()
Moves the robot calling the move_internal() implemented by the derived class.
Definition: RobotInterface.cpp:130
XBot::XBotInterface::setJointAcceleration
bool setJointAcceleration(const Eigen::VectorXd &qddot)
Sets the XBotInterface internal joint accelerations according to the provided vector,...
Definition: XBotInterface.cpp:1078
XBot::RobotInterface::getTimestampRx
double getTimestampRx() const
Get the RX timestamp: it corresponds to the last call to sense()
Definition: RobotInterface.cpp:260
XBot::ModelInterface
ModelInterface is an abstraction layer for a kinematic/dynamic model of a robot.
Definition: ModelInterface.h:46
XBot::XBotInterface::getJointVelocity
bool getJointVelocity(Eigen::VectorXd &qdot) const
Gets the robot joint velocities as an Eigen vector.
Definition: XBotInterface.cpp:762
XBot::RobotInterface::leg
RobotChain & leg(int leg_id)
Getter for the standard kinematic group leg: you can quickly access the i-th leg in the order specifi...
Definition: RobotInterface.cpp:201
XBot::RobotInterface::read_sensors
virtual bool read_sensors()=0
XBot::RobotInterface::move_internal
virtual bool move_internal()=0
XBot::XBotInterface::_ordered_joint_vector
std::vector< Joint::Ptr > _ordered_joint_vector
Definition: XBotInterface.h:1383
RobotChain.h
XBot::RobotInterface::getControlMode
void getControlMode(std::map< std::string, ControlMode > &control_mode) const
Definition: RobotInterface.cpp:285
XBot::XBotInterface::setPositionReference
bool setPositionReference(const Eigen::VectorXd &q)
Sets the XBotInterface internal joint position references according to the provided vector,...
Definition: XBotInterface.cpp:1121
XBot::AnyMapConstPtr
std::shared_ptr< const AnyMap > AnyMapConstPtr
Shared pointer to AnyMap.
Definition: TypedefAndEnums.h:84
XBot::RobotInterface
Definition: RobotInterface.h:36
XBot::RobotInterface::getTime
virtual double getTime() const =0
Getter for the time in the robot framework.
XBot::RobotInterface::sense_internal
virtual bool sense_internal(bool sync_references)=0
XBot::XBotInterface::getStiffness
bool getStiffness(Eigen::VectorXd &K) const
Gets the robot stiffness as an Eigen vector.
Definition: XBotInterface.cpp:808
XBot::XBotInterface::setVelocityReference
bool setVelocityReference(const Eigen::VectorXd &qdot)
Sets the XBotInterface internal joint velocity references according to the provided vector,...
Definition: XBotInterface.cpp:1163
XBot::ModelChain
Kinematic chain useful for a model abstraction.
Definition: ModelChain.h:34
XBot::RobotInterface::setReferenceFrom
bool setReferenceFrom(const ModelInterface &model, SyncFlags... flags)
Sets the robot references according to a ModelInterface.
Definition: RobotInterface.h:292
XBot::RobotInterface::~RobotInterface
virtual ~RobotInterface()=default
XBot::RobotInterface::post_init
virtual bool post_init()
Definition: RobotInterface.cpp:178
XBot::XBotInterface::getJointAcceleration
bool getJointAcceleration(Eigen::VectorXd &qddot) const
Gets the robot joint accelerations as an Eigen vector.
Definition: XBotInterface.cpp:773
XBot::XBotInterface::getPositionReference
bool getPositionReference(Eigen::VectorXd &q) const
Gets the robot position references as an Eigen vector.
Definition: XBotInterface.cpp:418
XBot::XBotInterface::setTemperature
bool setTemperature(const Eigen::VectorXd &temp)
Sets the XBotInterface internal joint temperatures according to the provided vector,...
Definition: XBotInterface.cpp:1149
XBot::RobotInterface::sense
bool sense(bool sync_model=true, bool sync_references=false)
Reads the current state of the robot calling sense_internal() and read_sensors() implemented by the d...
Definition: RobotInterface.cpp:115
XBot::RobotInterface::Ptr
std::shared_ptr< RobotInterface > Ptr
Definition: RobotInterface.h:41
XBot::RobotInterface::chain
RobotChain & chain(const std::string &chain_name)
Getter for the robot chain with a certain chain_name.
Definition: RobotInterface.cpp:220
XBot::XBotInterface::setMotorVelocity
bool setMotorVelocity(const Eigen::VectorXd &qdot)
Sets the XBotInterface internal motor velocities according to the provided vector,...
Definition: XBotInterface.cpp:1107
XBot::XBotInterface::setEffortReference
bool setEffortReference(const Eigen::VectorXd &tau)
Sets the XBotInterface internal joint effort references according to the provided vector,...
Definition: XBotInterface.cpp:1036
XBot::RobotInterface::model
ModelInterface & model()
Getter for the internal model instance.
Definition: RobotInterface.cpp:109
XBot
Definition: IXBotModel.h:20
XBot::RobotInterface::setControlMode
bool setControlMode(const ControlMode &control_mode)
Definition: RobotInterface.cpp:353
XBot::XBotInterface
Definition: XBotInterface.h:41