Namespace solo¶
-
namespace solo
Typedefs
-
template<int X>
using Vectord = Eigen::Matrix<double, X, 1>¶ Fixed-size double vector.
- Template Parameters:
X – Size of the Vector
-
typedef Eigen::Matrix<double, 1, 1> Vector1d¶
Vector2d shortcut for the eigen vector of size 1.
-
typedef Eigen::Matrix<double, 2, 1> Vector2d¶
Vector2d shortcut for the eigen vector of size 2.
-
typedef Eigen::Matrix<double, 6, 1> Vector6d¶
Vector2d shortcut for the eigen vector of size 6.
-
typedef Eigen::Matrix<double, 8, 1> Vector8d¶
Vector8d shortcut for the eigen vector of size 8.
-
typedef Eigen::Matrix<double, 12, 1> Vector12d¶
Vector8d shortcut for the eigen vector of size 12.
-
typedef std::shared_ptr<blmc_drivers::CanBus> CanBus_ptr¶
CanBus_ptr shortcut for the shared pointer CanBus type.
-
typedef std::shared_ptr<blmc_drivers::CanBusMotorBoard> CanBusMotorBoard_ptr¶
CanBusMotorBoard_Ptr shortcut for the shared pointer CanBus type.
-
typedef std::shared_ptr<blmc_drivers::MotorInterface> MotorInterface_ptr¶
MotorInterface_ptr shortcut for the shared pointer MotorInterface type.
-
typedef std::shared_ptr<blmc_drivers::Motor> Motor_ptr¶
Motor_ptr shortcut for the shared pointer Motor type.
-
typedef std::shared_ptr<blmc_drivers::SafeMotor> SafeMotor_ptr¶
SafeMotor_ptr shortcut for the shared pointer SafeMotor type.
-
typedef std::shared_ptr<blmc_drivers::AnalogSensor> Slider_ptr¶
Slider_ptr shortcut for the linear potentiometer analog sensor.
-
typedef std::shared_ptr<blmc_drivers::AnalogSensor> ContactSensor_ptr¶
ContactSensor_ptr shortcut for the contact sensor.
It is also an analog sensor
-
typedef std::shared_ptr<blmc_drivers::AnalogSensor> HeightSensor_ptr¶
HeightSensor_ptr shortcut for the height sensor.
It is also an analog sensor
-
typedef blmc_drivers::MotorInterface::MeasurementIndex mi¶
mi, this typedef is used to get the measurements from the blmc api
Enums
-
enum class SoloState¶
Values:
-
enumerator initial¶
-
enumerator ready¶
-
enumerator calibrate¶
-
enumerator initial
-
enumerator ready
-
enumerator calibrate
-
enumerator initial¶
-
enum class SoloState
Values:
-
enumerator initial
-
enumerator ready
-
enumerator calibrate
-
enumerator initial
-
enumerator ready
-
enumerator calibrate
-
enumerator initial
Functions
- std::atomic_bool CTRL_C_DETECTED (false)
This boolean is here to kill cleanly the application upon ctrl+c.
-
void my_handler(int)¶
This function is the callback upon a ctrl+c call from the terminal.
- Parameters:
s – is the id of the signal
-
void enable_ctrl_c()¶
Enable to kill the demos cleanly with a ctrl+c.
-
void print_vector(std::string v_name, const Eigen::Ref<const Eigen::VectorXd> v)¶
Usefull tool for the demos and programs in order to print data in real time.
- Parameters:
v_name – is a string defining the data to print.
v – the vector to print.
-
class DGMSolo12 : public DynamicGraphManager
- #include <dgm_solo12.hpp>
Public Functions
-
DGMSolo12()
DemoSingleMotor is the constructor.
-
~DGMSolo12()
~DemoSingleMotor is the destructor.
-
bool is_in_safety_mode()
This function make also sure that the joint velocity do not exceed a certain value.
-
void initialize_hardware_communication_process()
initialize_hardware_communication_process is the function that initialize the hardware.
-
void get_sensors_to_map(dynamic_graph_manager::VectorDGMap &map)
get_sensors_to_map acquieres the sensors data and feed it to the input/output map
- Param :
-
void set_motor_controls_from_map(const dynamic_graph_manager::VectorDGMap &map)
set_motor_controls_from_map reads the input map that contains the controls and send these controls to the hardware.
- Parameters:
map –
Ros callback for the callibration procedure.
Warning the robot will move to the next the joint index and back to “0” upon this call. Be sure that no controller are running in parallel.
- Parameters:
req – nothing
res – True if everything went well.
- Returns:
true if everything went well.
- Returns:
false if something went wrong.
-
void compute_safety_controls()
compute_safety_controls computes safety controls very fast in case the dynamic graph is taking to much computation time or has crashed.
-
DGMSolo12()
DemoSingleMotor is the constructor.
-
~DGMSolo12()
~DemoSingleMotor is the destructor.
-
bool is_in_safety_mode()
This function make also sure that the joint velocity do not exceed a certain value.
-
void initialize_hardware_communication_process()
initialize_hardware_communication_process is the function that initialize the hardware.
-
void get_sensors_to_map(dynamic_graph_manager::VectorDGMap &map)
get_sensors_to_map acquieres the sensors data and feed it to the input/output map
- Param :
-
void set_motor_controls_from_map(const dynamic_graph_manager::VectorDGMap &map)
set_motor_controls_from_map reads the input map that contains the controls and send these controls to the hardware.
- Parameters:
map –
-
void calibrate_joint_position_callback(mim_msgs::srv::JointCalibration::Request::SharedPtr req, mim_msgs::srv::JointCalibration::Response::SharedPtr res)
Ros callback for the callibration procedure.
Warning the robot will move to the next the joint index and back to “0” upon this call. Be sure that no controller are running in parallel.
- Parameters:
req – nothing
res – True if everything went well.
- Returns:
true if everything went well.
- Returns:
false if something went wrong.
-
void compute_safety_controls()
compute_safety_controls computes safety controls very fast in case the dynamic graph is taking to much computation time or has crashed.
-
DGMSolo12()
-
class DGMSolo8 : public DynamicGraphManager
- #include <dgm_solo8.hpp>
Public Functions
-
DGMSolo8()
DemoSingleMotor is the constructor.
-
~DGMSolo8()
~DemoSingleMotor is the destructor.
-
void initialize_hardware_communication_process()
This function make also sure that the joint velocity do not exceed a certain value.
initialize_hardware_communication_process is the function that initialize the hardware.
-
void get_sensors_to_map(dynamic_graph_manager::VectorDGMap &map)
get_sensors_to_map acquieres the sensors data and feed it to the input/output map
- Param :
-
void set_motor_controls_from_map(const dynamic_graph_manager::VectorDGMap &map)
set_motor_controls_from_map reads the input map that contains the controls and send these controls to the hardware.
- Parameters:
map –
- Parameters:
req –
res –
- Returns:
true
- Returns:
false
-
DGMSolo8()
DemoSingleMotor is the constructor.
-
~DGMSolo8()
~DemoSingleMotor is the destructor.
-
void initialize_hardware_communication_process()
This function make also sure that the joint velocity do not exceed a certain value.
initialize_hardware_communication_process is the function that initialize the hardware.
-
void get_sensors_to_map(dynamic_graph_manager::VectorDGMap &map)
get_sensors_to_map acquieres the sensors data and feed it to the input/output map
- Param :
-
void set_motor_controls_from_map(const dynamic_graph_manager::VectorDGMap &map)
set_motor_controls_from_map reads the input map that contains the controls and send these controls to the hardware.
- Parameters:
map –
-
void calibrate_joint_position_callback(mim_msgs::srv::JointCalibration::Request::SharedPtr req, mim_msgs::srv::JointCalibration::Response::SharedPtr res)
- Parameters:
req –
res –
- Returns:
true
- Returns:
false
-
DGMSolo8()
-
class DGMSolo8TI : public DynamicGraphManager
- #include <dgm_solo8ti.hpp>
Public Functions
-
DGMSolo8TI()
DemoSingleMotor is the constructor.
-
~DGMSolo8TI()
~DemoSingleMotor is the destructor.
-
void initialize_hardware_communication_process()
initialize_hardware_communication_process is the function that initialize the hardware.
-
void get_sensors_to_map(dynamic_graph_manager::VectorDGMap &map)
get_sensors_to_map acquieres the sensors data and feed it to the input/output map
- Param :
-
void set_motor_controls_from_map(const dynamic_graph_manager::VectorDGMap &map)
set_motor_controls_from_map reads the input map that contains the controls and send these controls to the hardware.
- Parameters:
map –
Handle the calibrate_joint callback.
- Parameters:
req – ROS request.
res – ROS response.
- Returns:
True if calibration was successful, false otherwise.
-
DGMSolo8TI()
DemoSingleMotor is the constructor.
-
~DGMSolo8TI()
~DemoSingleMotor is the destructor.
-
void initialize_hardware_communication_process()
initialize_hardware_communication_process is the function that initialize the hardware.
-
void get_sensors_to_map(dynamic_graph_manager::VectorDGMap &map)
get_sensors_to_map acquieres the sensors data and feed it to the input/output map
- Param :
-
void set_motor_controls_from_map(const dynamic_graph_manager::VectorDGMap &map)
set_motor_controls_from_map reads the input map that contains the controls and send these controls to the hardware.
- Parameters:
map –
-
void calibrate_joint_position_callback(mim_msgs::srv::JointCalibration::Request::SharedPtr req, mim_msgs::srv::JointCalibration::Response::SharedPtr res)
Handle the calibrate_joint callback.
- Parameters:
req – ROS request.
res – ROS response.
- Returns:
True if calibration was successful, false otherwise.
-
DGMSolo8TI()
-
class HWPSolo12 : public HardwareProcess
- #include <hwp_solo12.hpp>
Public Functions
-
HWPSolo12()
Constructor.
-
~HWPSolo12()
~Destructor.
-
bool is_in_safety_mode()
This function make also sure that the joint velocity do not exceed a certain value.
-
void initialize_drivers()
initialize_drivers is the function that initialize the hardware.
-
void get_sensors_to_map(dynamic_graph_manager::VectorDGMap &map)
get_sensors_to_map acquieres the sensors data and feed it to the input/output map
- Param :
-
void set_motor_controls_from_map(const dynamic_graph_manager::VectorDGMap &map)
set_motor_controls_from_map reads the input map that contains the controls and send these controls to the hardware.
- Parameters:
map –
-
void compute_safety_controls()
compute_safety_controls computes safety controls very fast in case the dynamic graph is taking to much computation time or has crashed.
-
void calibrate_joint_position(const solo::Vector12d &zero_to_index_angle)
Calibrate the robot joint position.
- Parameters:
zero_to_index_angle – is the angle between the theoretical zero and the next positive angle.
-
void calibrate_joint_position_from_yaml()
Calibrates the robot joint positions using the data from the yaml.
-
HWPSolo12()
Constructor.
-
~HWPSolo12()
~Destructor.
-
bool is_in_safety_mode()
This function make also sure that the joint velocity do not exceed a certain value.
-
void initialize_drivers()
initialize_drivers is the function that initialize the hardware.
-
void get_sensors_to_map(dynamic_graph_manager::VectorDGMap &map)
get_sensors_to_map acquieres the sensors data and feed it to the input/output map
- Param :
-
void set_motor_controls_from_map(const dynamic_graph_manager::VectorDGMap &map)
set_motor_controls_from_map reads the input map that contains the controls and send these controls to the hardware.
- Parameters:
map –
-
void compute_safety_controls()
compute_safety_controls computes safety controls very fast in case the dynamic graph is taking to much computation time or has crashed.
-
void calibrate_joint_position(const solo::Vector12d &zero_to_index_angle)
Calibrate the robot joint position.
- Parameters:
zero_to_index_angle – is the angle between the theoretical zero and the next positive angle.
-
void calibrate_joint_position_from_yaml()
Calibrates the robot joint positions using the data from the yaml.
-
HWPSolo12()
-
class Solo8TI
- #include <solo8ti.hpp>
Public Functions
-
Solo8TI()
Solo8 is the constructor of the class.
-
void initialize()
initialize the robot by setting aligning the motors and calibrate the sensors to 0
-
void send_target_joint_torque(const Eigen::Ref<Vector8d> target_joint_torque)
send_target_torques sends the target currents to the motors
-
void acquire_sensors()
acquire_sensors acquire all available sensors, WARNING !!!! this method has to be called prior to any getter to have up to date data.
-
bool calibrate(const Vector8d &home_offset_rad)
Calibrate the joints by moving to the next joint index position.
- Parameters:
home_offset_rad – This is the angle between the index and the zero pose.
- Returns:
true
- Returns:
false
-
inline const Eigen::Ref<Vector8d> get_motor_inertias()
Joint properties.
get_motor_inertias
- Returns:
the motor inertias
-
inline const Eigen::Ref<Vector8d> get_motor_torque_constants()
get_motor_torque_constants
- Returns:
the torque constants of each motor
-
inline const Eigen::Ref<Vector8d> get_joint_gear_ratios()
get_joint_gear_ratios
- Returns:
the joint gear ratios
-
inline const Eigen::Ref<Vector8d> get_motor_max_current()
get_max_torque
- Returns:
the max torque that has been hardcoded in the constructor of this class. TODO: parametrize this via yaml or something else.
-
inline const Eigen::Ref<Vector8d> get_joint_positions()
Sensor Data.
get_joint_positions
- Returns:
the joint angle of each module WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vector8d> get_joint_velocities()
get_joint_velocities
- Returns:
the joint velocities WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vector8d> get_joint_torques()
get_joint_torques
- Returns:
the joint torques WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vector8d> get_joint_target_torques()
get_joint_torques
- Returns:
the target joint torques WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vector8d> get_joint_encoder_index()
get_joint_encoder_index
- Returns:
the position of the index of the encoders a the motor level WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_contact_sensors_states()
get_contact_sensors_states
- Returns:
the state of the contacts states WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_slider_positions()
get_slider_positions
- Returns:
the current sliders positions. WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const std::array<bool, 8> &get_motor_enabled()
Hardware Status.
get_motor_enabled
- Returns:
This gives the status (enabled/disabled) of each motors using the joint ordering convention.
-
inline const std::array<bool, 8> &get_motor_ready()
get_motor_ready
- Returns:
This gives the status (enabled/disabled) of each motors using the joint ordering convention.
-
inline const std::array<bool, 4> &get_motor_board_enabled()
get_motor_board_enabled
- Returns:
This gives the status (enabled/disabled of the onboard control cards).
-
inline const std::array<int, 4> &get_motor_board_errors()
get_motor_board_errors
- Returns:
This gives the status (enabled/disabled of the onboard control cards).
-
Solo8TI()
Solo8 is the constructor of the class.
-
void initialize()
initialize the robot by setting aligning the motors and calibrate the sensors to 0
-
void send_target_joint_torque(const Eigen::Ref<Vector8d> target_joint_torque)
send_target_torques sends the target currents to the motors
-
void acquire_sensors()
acquire_sensors acquire all available sensors, WARNING !!!! this method has to be called prior to any getter to have up to date data.
-
bool calibrate(const Vector8d &home_offset_rad)
Calibrate the joints by moving to the next joint index position.
- Parameters:
home_offset_rad – This is the angle between the index and the zero pose.
- Returns:
true
- Returns:
false
-
inline const Eigen::Ref<Vector8d> get_motor_inertias()
Joint properties.
get_motor_inertias
- Returns:
the motor inertias
-
inline const Eigen::Ref<Vector8d> get_motor_torque_constants()
get_motor_torque_constants
- Returns:
the torque constants of each motor
-
inline const Eigen::Ref<Vector8d> get_joint_gear_ratios()
get_joint_gear_ratios
- Returns:
the joint gear ratios
-
inline const Eigen::Ref<Vector8d> get_motor_max_current()
get_max_torque
- Returns:
the max torque that has been hardcoded in the constructor of this class. TODO: parametrize this via yaml or something else.
-
inline const Eigen::Ref<Vector8d> get_joint_positions()
Sensor Data.
get_joint_positions
- Returns:
the joint angle of each module WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vector8d> get_joint_velocities()
get_joint_velocities
- Returns:
the joint velocities WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vector8d> get_joint_torques()
get_joint_torques
- Returns:
the joint torques WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vector8d> get_joint_target_torques()
get_joint_torques
- Returns:
the target joint torques WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vector8d> get_joint_encoder_index()
get_joint_encoder_index
- Returns:
the position of the index of the encoders a the motor level WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_contact_sensors_states()
get_contact_sensors_states
- Returns:
the state of the contacts states WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_slider_positions()
get_slider_positions
- Returns:
the current sliders positions. WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const std::array<bool, 8> &get_motor_enabled()
Hardware Status.
get_motor_enabled
- Returns:
This gives the status (enabled/disabled) of each motors using the joint ordering convention.
-
inline const std::array<bool, 8> &get_motor_ready()
get_motor_ready
- Returns:
This gives the status (enabled/disabled) of each motors using the joint ordering convention.
-
inline const std::array<bool, 4> &get_motor_board_enabled()
get_motor_board_enabled
- Returns:
This gives the status (enabled/disabled of the onboard control cards).
-
inline const std::array<int, 4> &get_motor_board_errors()
get_motor_board_errors
- Returns:
This gives the status (enabled/disabled of the onboard control cards).
-
Solo8TI()
-
template<int X>
class SoloX - #include <solox.hpp>
Interface for the Solo robots using the master board.
This class is templated with the number of joints and can be used for both Solo8 and Solo12 by setting the corresponding number.
Solo8¶
TODO
Solo12¶
Mapping between the DOF and driver boards + motor ports:
FL_HAA: motor board 0, motor port 0, motor index 0
FL_HFE: motor board 1, motor port 1, motor index 3
FL_KFE: motor board 1, motor port 0, motor index 2
FR_HAA: motor board 0, motor port 1, motor index 1
FR_HFE: motor board 2, motor port 1, motor index 5
FR_KFE: motor board 2, motor port 0, motor index 4
HL_HAA: motor board 3, motor port 0, motor index 6
HL_HFE: motor board 4, motor port 1, motor index 9
HL_KFE: motor board 4, motor port 0, motor index 8
HR_HAA: motor board 3, motor port 1, motor index 7
HR_HFE: motor board 5, motor port 1, motor index 11
HR_KFE: motor board 5, motor port 0, motor index 10
This class is templated with the number of joints and can be used for both Solo8 and Solo12 by setting the corresponding number.
Solo8¶
TODO
Solo12¶
Mapping between the DOF and driver boards + motor ports:
FL_HAA: motor board 0, motor port 0, motor index 0
FL_HFE: motor board 1, motor port 1, motor index 3
FL_KFE: motor board 1, motor port 0, motor index 2
FR_HAA: motor board 0, motor port 1, motor index 1
FR_HFE: motor board 2, motor port 1, motor index 5
FR_KFE: motor board 2, motor port 0, motor index 4
HL_HAA: motor board 3, motor port 0, motor index 6
HL_HFE: motor board 4, motor port 1, motor index 9
HL_KFE: motor board 4, motor port 0, motor index 8
HR_HAA: motor board 3, motor port 1, motor index 7
HR_HFE: motor board 5, motor port 1, motor index 11
HR_KFE: motor board 5, motor port 0, motor index 10
- Template Parameters:
X – Number of joints of the robot. Should be either 8 or 12.
X – Number of joints of the robot. Should be either 8 or 12.
Public Functions
-
SoloX()
Solo is the constructor of the class.
-
void initialize(const std::string &network_id, const std::string &slider_box_port = "auto")
Initialize the robot by setting aligning the motors and calibrate the sensors to 0.
- Parameters:
network_id – Name of the network interface for connection to the robot.
slider_box_port – Name of the serial port to which the slider box is connected. Set to “” or “none” if no slider box is used. Set to “auto” to auto-detect the port.
-
void set_max_current(const double &max_current)
Sets the maximum joint torques.
-
void wait_until_ready()
Wait that the robot enters into the ready states.
-
bool is_ready()
Check if the robot is ready.
-
void send_target_joint_torque(const Eigen::Ref<Vectord<X>> target_joint_torque)
send_target_torques sends the target currents to the motors.
-
void send_target_joint_position(const Eigen::Ref<Vectord<X>> target_joint_position)
Sets the desired joint position of the P controller running on the card.
-
void send_target_joint_velocity(const Eigen::Ref<Vectord<X>> target_joint_velocity)
Sets the desired joint velocity of the D controller running on the card.
-
void send_target_joint_position_gains(const Eigen::Ref<Vectord<X>> target_joint_position_gains)
Sets the desired joint position gain P for the P controller running on the card.
-
void send_target_joint_velocity_gains(const Eigen::Ref<Vectord<X>> target_joint_velocity_gains)
Sets the desired joint velocity gain D for the D controller running on the card.
-
void acquire_sensors()
acquire_sensors acquire all available sensors, WARNING !!!! this method has to be called prior to any getter to have up to date data.
-
bool request_calibration(const Vectord<X> &home_offset_rad)
Asynchronously request for the calibration.
- Parameters:
home_offset_rad – This is the angle between the index and the zero pose.
- Returns:
true in case of success.
- Returns:
false in case of failure.
-
inline const Eigen::Ref<Vectord<X>> get_motor_inertias()
Joint properties.
get_motor_inertias in [kg m^2]
- Returns:
Motor inertias.
-
inline const Eigen::Ref<Vectord<X>> get_motor_torque_constants()
get_motor_torque_constants in []
- Returns:
Torque constants of each motor.
-
inline const Eigen::Ref<Vectord<X>> get_joint_gear_ratios()
get_joint_gear_ratios
- Returns:
Joint gear ratios
-
inline const Eigen::Ref<Vectord<X>> get_motor_max_current()
get_max_torque
- Todo:
Parametrize the maximum current via yaml or something else.
- Returns:
the max torque that has been hardcoded in the constructor of this class.
-
inline const Eigen::Ref<Vectord<X>> get_joint_positions()
Sensor Data.
get_joint_positions
- Returns:
the joint angle of each module WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vectord<X>> get_joint_velocities()
get_joint_velocities
- Returns:
the joint velocities WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vectord<X>> get_joint_torques()
get_joint_torques
- Returns:
the joint torques WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vectord<X>> get_joint_target_torques()
get_joint_torques
- Returns:
the target joint torques WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vectord<X>> get_joint_encoder_index()
get_joint_encoder_index
- Returns:
the position of the index of the encoders a the motor level WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_contact_sensors_states()
get_contact_sensors_states
- Returns:
the state of the contacts states WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_slider_positions()
get_slider_positions
- Returns:
the current sliders positions. WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector3d> get_imu_accelerometer()
base accelerometer from imu.
- Returns:
WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector3d> get_imu_gyroscope()
base gyroscope from imu.
- Returns:
WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_imu_attitude()
base attitude quaternion (ordered {x, y, z, w}) from imu.
- Returns:
WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector3d> get_imu_linear_acceleration()
base linear acceleration from imu.
- Returns:
WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const std::array<bool, X> &get_motor_enabled()
get_motor_enabled
- Returns:
This gives the status (enabled/disabled) of each motors using the joint ordering convention.
-
inline const std::array<bool, X> &get_motor_ready()
get_motor_ready
- Returns:
This gives the status (enabled/disabled) of each motors using the joint ordering convention.
-
inline const std::array<bool, X / 2> &get_motor_board_enabled()
get_motor_board_enabled
- Returns:
This gives the status (enabled/disabled of the onboard control cards).
-
inline const std::array<int, X / 2> &get_motor_board_errors()
get_motor_board_errors
- Returns:
This gives the status (enabled/disabled of the onboard control cards).
-
inline bool has_error() const
has_error
- Returns:
Returns true if the robot hardware has an error, false otherwise.
-
inline bool is_calibrating()
is_calibrating()
- Returns:
Returns true if the calibration procedure is running right now.
-
inline int get_num_sent_command_packets() const
Get total number of command packets sent to the robot.
-
inline int get_num_lost_command_packets() const
Get number of lost command packets.
-
inline int get_num_sent_sensor_packets() const
Get total number of sensor packets sent by the robot.
-
inline int get_num_lost_sensor_packets() const
Get number of lost sensor packets.
-
SoloX()
Solo is the constructor of the class.
-
void initialize(const std::string &network_id, const std::string &slider_box_port = "auto")
Initialize the robot by setting aligning the motors and calibrate the sensors to 0.
- Parameters:
network_id – Name of the network interface for connection to the robot.
slider_box_port – Name of the serial port to which the slider box is connected. Set to “” or “none” if no slider box is used. Set to “auto” to auto-detect the port.
-
void set_max_current(const double &max_current)
Sets the maximum joint torques.
-
void wait_until_ready()
Wait that the robot enters into the ready states.
-
bool is_ready()
Check if the robot is ready.
-
void send_target_joint_torque(const Eigen::Ref<Vectord<X>> target_joint_torque)
send_target_torques sends the target currents to the motors.
-
void send_target_joint_position(const Eigen::Ref<Vectord<X>> target_joint_position)
Sets the desired joint position of the P controller running on the card.
-
void send_target_joint_velocity(const Eigen::Ref<Vectord<X>> target_joint_velocity)
Sets the desired joint velocity of the D controller running on the card.
-
void send_target_joint_position_gains(const Eigen::Ref<Vectord<X>> target_joint_position_gains)
Sets the desired joint position gain P for the P controller running on the card.
-
void send_target_joint_velocity_gains(const Eigen::Ref<Vectord<X>> target_joint_velocity_gains)
Sets the desired joint velocity gain D for the D controller running on the card.
-
void acquire_sensors()
acquire_sensors acquire all available sensors, WARNING !!!! this method has to be called prior to any getter to have up to date data.
-
bool request_calibration(const Vectord<X> &home_offset_rad)
Asynchronously request for the calibration.
- Parameters:
home_offset_rad – This is the angle between the index and the zero pose.
- Returns:
true in case of success.
- Returns:
false in case of failure.
-
inline const Eigen::Ref<Vectord<X>> get_motor_inertias()
Joint properties.
get_motor_inertias in [kg m^2]
- Returns:
Motor inertias.
-
inline const Eigen::Ref<Vectord<X>> get_motor_torque_constants()
get_motor_torque_constants in []
- Returns:
Torque constants of each motor.
-
inline const Eigen::Ref<Vectord<X>> get_joint_gear_ratios()
get_joint_gear_ratios
- Returns:
Joint gear ratios
-
inline const Eigen::Ref<Vectord<X>> get_motor_max_current()
get_max_torque
- Todo:
Parametrize the maximum current via yaml or something else.
- Returns:
the max torque that has been hardcoded in the constructor of this class.
-
inline const Eigen::Ref<Vectord<X>> get_joint_positions()
Sensor Data.
get_joint_positions
- Returns:
the joint angle of each module WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vectord<X>> get_joint_velocities()
get_joint_velocities
- Returns:
the joint velocities WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vectord<X>> get_joint_torques()
get_joint_torques
- Returns:
the joint torques WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vectord<X>> get_joint_target_torques()
get_joint_torques
- Returns:
the target joint torques WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Vectord<X>> get_joint_encoder_index()
get_joint_encoder_index
- Returns:
the position of the index of the encoders a the motor level WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_contact_sensors_states()
get_contact_sensors_states
- Returns:
the state of the contacts states WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_slider_positions()
get_slider_positions
- Returns:
the current sliders positions. WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector3d> get_imu_accelerometer()
base accelerometer from imu.
- Returns:
WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector3d> get_imu_gyroscope()
base gyroscope from imu.
- Returns:
WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector4d> get_imu_attitude()
base attitude quaternion (ordered {x, y, z, w}) from imu.
- Returns:
WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const Eigen::Ref<Eigen::Vector3d> get_imu_linear_acceleration()
base linear acceleration from imu.
- Returns:
WARNING !!!! The method <acquire_sensors>”()” has to be called prior to any getter to have up to date data.
-
inline const std::array<bool, X> &get_motor_enabled()
get_motor_enabled
- Returns:
This gives the status (enabled/disabled) of each motors using the joint ordering convention.
-
inline const std::array<bool, X> &get_motor_ready()
get_motor_ready
- Returns:
This gives the status (enabled/disabled) of each motors using the joint ordering convention.
-
inline const std::array<bool, X / 2> &get_motor_board_enabled()
get_motor_board_enabled
- Returns:
This gives the status (enabled/disabled of the onboard control cards).
-
inline const std::array<int, X / 2> &get_motor_board_errors()
get_motor_board_errors
- Returns:
This gives the status (enabled/disabled of the onboard control cards).
-
inline bool has_error() const
has_error
- Returns:
Returns true if the robot hardware has an error, false otherwise.
-
inline bool is_calibrating()
is_calibrating()
- Returns:
Returns true if the calibration procedure is running right now.
-
inline int get_num_sent_command_packets() const
Get total number of command packets sent to the robot.
-
inline int get_num_lost_command_packets() const
Get number of lost command packets.
-
inline int get_num_sent_sensor_packets() const
Get total number of sensor packets sent by the robot.
-
inline int get_num_lost_sensor_packets() const
Get number of lost sensor packets.
Public Static Attributes
-
static const std::string SLIDER_BOX_DISABLED = "none"
Set slider box port to this value to disable it.
-
static const std::string LOGGER_NAME = "solo/Solo"
Name of the spdlog logger used by the class.
-
template<int COUNT>
class SpiJointModules - #include <spi_joint_module.hpp>
This class defines an interface to a collection of BLMC joints.
It creates a BLMCJointModule for every blmc_driver::MotorInterface provided.
Public Types
-
typedef Eigen::Matrix<double, COUNT, 1> Vector
Defines a static Eigen vector type in order to define the interface.
-
typedef Eigen::Matrix<double, COUNT, 1> Vector
Defines a static Eigen vector type in order to define the interface.
Public Functions
Construct a new SpiJointModules object.
-
inline void enable()
Enable all motors and motor drivers used by the joint module.
-
inline bool is_ready()
Checks if all motors report ready.
- Returns:
True if all motors are ready, false otherwise.
-
inline std::array<bool, COUNT> get_motor_enabled()
-
inline std::array<bool, COUNT> get_motor_ready()
-
inline void send_torques()
Send the registered torques to all modules.
-
inline void acquire_sensors()
Updates the measurements based on the lastest package from the master board.
-
inline void set_torques(const Vector &desired_torques)
Register the joint torques to be sent for all modules.
- Parameters:
desired_torques – (Nm)
-
inline Vector get_max_torques()
Get the maximum admissible joint torque that can be applied.
- Returns:
Vector (N/m)
-
inline Vector get_sent_torques() const
Get the previously sent torques.
- Returns:
Vector (Nm)
-
inline Vector get_measured_torques() const
Get the measured joint torques.
- Returns:
Vector (Nm)
-
inline Vector get_measured_angles() const
Get the measured joint angles.
- Returns:
Vector (rad)
-
inline Vector get_measured_velocities() const
Get the measured joint velocities.
- Returns:
Vector (rad/s)
-
inline void set_zero_angles(const Vector &zero_angles)
Set the zero_angles.
These are the joint angles between the starting pose and the zero theoretical pose of the urdf.
- Parameters:
zero_angles – (rad)
-
inline Vector get_zero_angles() const
Get the zero_angles.
These are the joint angles between the starting pose and the zero theoretical pose of the urdf.
- Returns:
Vector (rad)
-
inline Vector get_measured_index_angles() const
Get the index_angles.
There is one index per motor rotation so there are gear_ratio indexes per joint rotation.
- Returns:
Vector (rad)
-
inline SpiJointModules(std::shared_ptr<MasterBoardInterface> robot_if, std::array<int, COUNT> &motor_to_card_index, std::array<int, COUNT> &motor_to_card_port_index, const Vector &motor_constants, const Vector &gear_ratios, const Vector &zero_angles, const Vector &max_currents, std::array<bool, COUNT> reverse_polarities)
Construct a new SpiJointModules object.
-
inline void enable()
Enable all motors and motor drivers used by the joint module.
-
inline bool is_ready()
Checks if all motors report ready.
- Returns:
True if all motors are ready, false otherwise.
-
inline std::array<bool, COUNT> get_motor_enabled()
-
inline std::array<bool, COUNT> get_motor_ready()
-
inline void send_torques()
Send the registered torques to all modules.
-
inline void acquire_sensors()
Updates the measurements based on the lastest package from the master board.
-
inline void set_torques(const Vector &desired_torques)
Register the joint torques to be sent for all modules.
- Parameters:
desired_torques – (Nm)
-
inline Vector get_max_torques()
Get the maximum admissible joint torque that can be applied.
- Returns:
Vector (N/m)
-
inline Vector get_sent_torques() const
Get the previously sent torques.
- Returns:
Vector (Nm)
-
inline Vector get_measured_torques() const
Get the measured joint torques.
- Returns:
Vector (Nm)
-
inline Vector get_measured_angles() const
Get the measured joint angles.
- Returns:
Vector (rad)
-
inline Vector get_measured_velocities() const
Get the measured joint velocities.
- Returns:
Vector (rad/s)
-
inline void set_zero_angles(const Vector &zero_angles)
Set the zero_angles.
These are the joint angles between the starting pose and the zero theoretical pose of the urdf.
- Parameters:
zero_angles – (rad)
-
inline Vector get_zero_angles() const
Get the zero_angles.
These are the joint angles between the starting pose and the zero theoretical pose of the urdf.
- Returns:
Vector (rad)
-
inline Vector get_measured_index_angles() const
Get the index_angles.
There is one index per motor rotation so there are gear_ratio indexes per joint rotation.
- Returns:
Vector (rad)
-
typedef Eigen::Matrix<double, COUNT, 1> Vector
-
template<class ROBOT_TYPE>
struct ThreadCalibrationData - #include <common_demo_header.hpp>
This small structure is used for reading the calibration parameters for the calibrations demos.
- Template Parameters:
ROBOT_TYPE –
Public Functions
-
template<int X>