XBotInterface
2.4.1
XBotInterface provides a generic API to model and control a robot.
|
Go to the documentation of this file.
20 #ifndef __ROBOT_INTERFACE_H__
21 #define __ROBOT_INTERFACE_H__
41 typedef std::shared_ptr<RobotInterface>
Ptr;
42 typedef std::shared_ptr<const RobotInterface>
ConstPtr;
63 const std::string& robot_name =
"");
73 const std::string& robot_name =
"",
75 const std::string& framework =
"");
93 virtual double getTime()
const = 0;
111 bool sense(
bool sync_model =
true,
112 bool sync_references =
false);
181 template <
typename... SyncFlags>
187 bool setControlMode(
const std::map<std::string, ControlMode>& control_mode);
188 bool setControlMode(
const std::map<int, ControlMode>& control_mode);
191 void getControlMode(std::map<std::string, ControlMode>& control_mode)
const;
192 void getControlMode(std::map<int, ControlMode>& control_mode)
const;
273 std::map<std::string, XBot::RobotChain::Ptr> _robot_chain_map;
280 static std::map<std::string, RobotInterface::Ptr> _instance_ptr_map;
282 std::vector<std::string> _model_ordered_chain_name;
291 template <
typename... SyncFlags>
297 for (
const auto & c : model._model_chain_map) {
299 const std::string &chain_name = c.first;
302 if(_robot_chain_map.count(chain_name))
304 _robot_chain_map.at(chain_name)->setReferenceFrom(chain, flags...);
313 #endif // __ROBOT_INTERFACE_H__
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
Definition: ConfigOptions.h:36
bool getJointEffort(Eigen::VectorXd &tau) const
Gets the robot joint efforts as an Eigen vector.
Definition: XBotInterface.cpp:740
virtual bool isRunning() const =0
...
bool getEffortReference(Eigen::VectorXd &tau) const
Gets the robot effort references as an Eigen vector.
Definition: XBotInterface.cpp:751
bool getMotorPosition(Eigen::VectorXd &q) const
Gets the robot motor positions as an Eigen vector.
Definition: XBotInterface.cpp:786
RobotChain & operator()(const std::string &chain_name)
Getter for the robot chain with a certain chain_name.
Definition: RobotInterface.cpp:211
bool getJointPosition(Eigen::VectorXd &q) const
Gets the robot joint positions as an Eigen vector.
Definition: XBotInterface.cpp:348
Kinematic chain useful for a robot abstraction.
Definition: RobotChain.h:33
double getTimestampTx() const
Get the TX timestamp: it corresponds to the last call to move()
Definition: RobotInterface.cpp:265
virtual bool sense_hands()=0
std::shared_ptr< ModelInterface > Ptr
Shared pointer to a ModelInterface.
Definition: ModelInterface.h:56
std::map< std::string, XBot::KinematicChain::Ptr > _chain_map
Definition: XBotInterface.h:1382
bool getMotorVelocity(Eigen::VectorXd &qdot) const
Gets the robot motor velocities as an Eigen vector.
Definition: XBotInterface.cpp:797
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
RobotInterface()
Default constructor.
Definition: RobotInterface.cpp:31
Definition: ControlMode.h:28
bool getTemperature(Eigen::VectorXd &temp) const
Gets the robot joint temperatures as an Eigen vector.
Definition: XBotInterface.cpp:819
std::vector< std::string > _ordered_chain_names
Definition: XBotInterface.h:1391
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
virtual bool set_control_mode_internal(int joint_id, const ControlMode &control_mode)
Definition: RobotInterface.cpp:270
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
bool sync(const XBotInterface &other, SyncFlags... flags)
Synchronize the current XBotInterface with another XBotInterface object: only the common chains will ...
Definition: XBotInterface.h:1421
std::shared_ptr< const RobotInterface > ConstPtr
Definition: RobotInterface.h:42
virtual bool init_robot(const ConfigOptions &config)=0
static void clearRobotMap(void)
Definition: RobotInterface.cpp:35
bool getDamping(Eigen::VectorXd &D) const
Gets the robot damping as an Eigen vector.
Definition: XBotInterface.cpp:729
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
bool getVelocityReference(Eigen::VectorXd &qdot) const
Gets the robot velocity references as an Eigen vector.
Definition: XBotInterface.cpp:830
bool setJointVelocity(const Eigen::VectorXd &qdot)
Sets the XBotInterface internal joint velocities according to the provided vector,...
Definition: XBotInterface.cpp:1064
RobotInterface & operator=(const RobotInterface &other)=delete
virtual bool move_hands()=0
static RobotInterface::Ptr getRobot(const ConfigOptions &config, const std::string &robot_name="")
...
Definition: RobotInterface.cpp:43
const std::map< std::string, XBot::KinematicChain::Ptr > & getChainMap() const
Getter for the chain map inside the XBotInterface.
Definition: XBotInterface.cpp:1389
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
bool move()
Moves the robot calling the move_internal() implemented by the derived class.
Definition: RobotInterface.cpp:130
bool setJointAcceleration(const Eigen::VectorXd &qddot)
Sets the XBotInterface internal joint accelerations according to the provided vector,...
Definition: XBotInterface.cpp:1078
double getTimestampRx() const
Get the RX timestamp: it corresponds to the last call to sense()
Definition: RobotInterface.cpp:260
ModelInterface is an abstraction layer for a kinematic/dynamic model of a robot.
Definition: ModelInterface.h:46
bool getJointVelocity(Eigen::VectorXd &qdot) const
Gets the robot joint velocities as an Eigen vector.
Definition: XBotInterface.cpp:762
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
virtual bool read_sensors()=0
virtual bool move_internal()=0
std::vector< Joint::Ptr > _ordered_joint_vector
Definition: XBotInterface.h:1383
void getControlMode(std::map< std::string, ControlMode > &control_mode) const
Definition: RobotInterface.cpp:285
bool setPositionReference(const Eigen::VectorXd &q)
Sets the XBotInterface internal joint position references according to the provided vector,...
Definition: XBotInterface.cpp:1121
std::shared_ptr< const AnyMap > AnyMapConstPtr
Shared pointer to AnyMap.
Definition: TypedefAndEnums.h:84
Definition: RobotInterface.h:36
virtual double getTime() const =0
Getter for the time in the robot framework.
virtual bool sense_internal(bool sync_references)=0
bool getStiffness(Eigen::VectorXd &K) const
Gets the robot stiffness as an Eigen vector.
Definition: XBotInterface.cpp:808
bool setVelocityReference(const Eigen::VectorXd &qdot)
Sets the XBotInterface internal joint velocity references according to the provided vector,...
Definition: XBotInterface.cpp:1163
Kinematic chain useful for a model abstraction.
Definition: ModelChain.h:34
bool setReferenceFrom(const ModelInterface &model, SyncFlags... flags)
Sets the robot references according to a ModelInterface.
Definition: RobotInterface.h:292
virtual ~RobotInterface()=default
virtual bool post_init()
Definition: RobotInterface.cpp:178
bool getJointAcceleration(Eigen::VectorXd &qddot) const
Gets the robot joint accelerations as an Eigen vector.
Definition: XBotInterface.cpp:773
bool getPositionReference(Eigen::VectorXd &q) const
Gets the robot position references as an Eigen vector.
Definition: XBotInterface.cpp:418
bool setTemperature(const Eigen::VectorXd &temp)
Sets the XBotInterface internal joint temperatures according to the provided vector,...
Definition: XBotInterface.cpp:1149
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
std::shared_ptr< RobotInterface > Ptr
Definition: RobotInterface.h:41
RobotChain & chain(const std::string &chain_name)
Getter for the robot chain with a certain chain_name.
Definition: RobotInterface.cpp:220
bool setMotorVelocity(const Eigen::VectorXd &qdot)
Sets the XBotInterface internal motor velocities according to the provided vector,...
Definition: XBotInterface.cpp:1107
bool setEffortReference(const Eigen::VectorXd &tau)
Sets the XBotInterface internal joint effort references according to the provided vector,...
Definition: XBotInterface.cpp:1036
ModelInterface & model()
Getter for the internal model instance.
Definition: RobotInterface.cpp:109
Definition: IXBotModel.h:20
bool setControlMode(const ControlMode &control_mode)
Definition: RobotInterface.cpp:353
Definition: XBotInterface.h:41