dynamixel_hardware_interface::MotorBase#
Base class for controlling dynamixel motor.
#include <motor_base.hpp>
Inherited by dynamixel_hardware_interface::motors::XW540_T260
Public Functions#
Name | |
---|---|
~MotorBase() Destroy the Motor Base object. |
|
virtual Result | updatePresentTemperature() Execute update present temperature command to the motor. |
virtual Result | updateJointVelocity() Execute update joint velocity command to the motor. |
virtual Result | updateJointPosition() Execute update joint position command to the motor. |
virtual Result | torqueEnable(bool enable) Execute torqu_enabled command to the motor. |
virtual Result | setJointPositionLimit(double max_joint_limit, double min_joint_limit) |
virtual Result | setGoalPosition(double goal_position) Execute goal_position command to the motor. |
virtual Result | setCurrentGoalPosition() Execute goal_position command to the motor without update current goal position. |
bool | operationSupports(const Operation & operation) Check the operation is support in your motor. |
virtual std::vector< Operation > | getSupportedOperations() Get list of supported Operations in your motor. |
virtual double | getJointPosition() const Get current joint position of the motor. |
virtual double | getGoalPosition() const Get current goal position of the motor. |
virtual Result | configure() Configure dynamixel motor. |
virtual void | appendStateInterfaces(std::vector< hardware_interface::StateInterface > & interfaces) Append state interface described in the URDF file. |
virtual void | appendCommandInterfaces(std::vector< hardware_interface::CommandInterface > & interfaces) Append command interface described in the URDF file. |
template \<typename AddressTable > | MotorBase(const SupportedMotors & motor_type, const std::string & joint_name, const bool enable_dummy, const AddressTable & table, int baudrate, uint8_t id, double max_joint_limit, double min_joint_limit, std::shared_ptr< dynamixel::PortHandler > port_handler, std::shared_ptr< dynamixel::PacketHandler > packet_handler) Construct a new Motor Base object. |
Protected Functions#
Name | |
---|---|
virtual double | valueToTemperature(uint8_t value) const |
virtual double | valueToTemperature(uint16_t value) const |
virtual double | valueToTemperature(uint32_t value) const |
virtual double | valueToRpm(uint8_t value) const |
virtual double | valueToRpm(uint16_t value) const |
virtual double | valueToRpm(uint32_t value) const |
void | rpmToVelocity(double rpm, double & radian) const |
template \<typename T >T | radianToPosition(double radian) const |
uint16_t | radianToPosition(double radian) const |
virtual void | radianToPosition(double radian, uint8_t & value) const |
virtual void | radianToPosition(double radian, uint16_t & value) const |
virtual void | radianToPosition(double radian, uint32_t & value) const |
virtual double | positionToRadian(const uint8_t position) const |
virtual double | positionToRadian(const uint16_t position) const |
virtual double | positionToRadian(const uint32_t position) const |
Result | getResult(int communication_result, uint8_t packet_error) |
MotorBase() Construct a new Motor Base object. |
Public Attributes#
Name | |
---|---|
const SupportedMotors | motor_type Describe the type of the motor. |
const double | min_joint_limit |
const double | max_joint_limit |
const std::string | joint_name Name of the joint which the motor is attaching to. |
const uint8_t | id Id of the dynamixel motor. |
const bool | enable_dummy If true, you can communicate with virtual dinamixel motor. |
const int | baudrate Baudrate of the serial communication. |
Protected Attributes#
Name | |
---|---|
double | present_temperature_ |
std::shared_ptr< dynamixel::PortHandler > | port_handler_ |
std::shared_ptr< dynamixel::PacketHandler > | packet_handler_ |
double | joint_velocity_ |
double | joint_position_ |
double | goal_velocity_ |
double | goal_position_ |
std::shared_ptr< AddressTableBase > | address_table_ |
Public Functions Documentation#
function ~MotorBase#
~MotorBase()
Destroy the Motor Base object.
function updatePresentTemperature#
virtual Result updatePresentTemperature()
Execute update present temperature command to the motor.
Return: Result
function updateJointVelocity#
virtual Result updateJointVelocity()
Execute update joint velocity command to the motor.
Return: Result
function updateJointPosition#
virtual Result updateJointPosition()
Execute update joint position command to the motor.
Return: Result result of the command.
function torqueEnable#
virtual Result torqueEnable(
bool enable
)
Execute torqu_enabled command to the motor.
Parameters:
- enable if true, enable torque.
Return: Result result of the command.
function setJointPositionLimit#
virtual Result setJointPositionLimit(
double max_joint_limit,
double min_joint_limit
)
function setGoalPosition#
virtual Result setGoalPosition(
double goal_position
)
Execute goal_position command to the motor.
Parameters:
- goal_position goal position angle in radian.
Return: Result result of the command.
function setCurrentGoalPosition#
inline virtual Result setCurrentGoalPosition()
Execute goal_position command to the motor without update current goal position.
Return: Result result of the command.
function operationSupports#
bool operationSupports(
const Operation & operation
)
Check the operation is support in your motor.
Parameters:
- operation Operation which you want to execute.
Return:
- true Operation supports.
- false Operation does not support.
function getSupportedOperations#
virtual std::vector< Operation > getSupportedOperations()
Get list of supported Operations in your motor.
Return: std::vector
function getJointPosition#
inline virtual double getJointPosition() const
Get current joint position of the motor.
Return: double Current joint position of the motor in radian.
function getGoalPosition#
inline virtual double getGoalPosition() const
Get current goal position of the motor.
Return: double Current goal position of the motor in radian.
function configure#
virtual Result configure()
Configure dynamixel motor.
Return: Result result of the configuration.
function appendStateInterfaces#
virtual void appendStateInterfaces(
std::vector< hardware_interface::StateInterface > & interfaces
)
Append state interface described in the URDF file.
Parameters:
- interfaces List of state interface.
function appendCommandInterfaces#
virtual void appendCommandInterfaces(
std::vector< hardware_interface::CommandInterface > & interfaces
)
Append command interface described in the URDF file.
Parameters:
- interfaces List of command interface.
function MotorBase#
template <typename AddressTable >
inline MotorBase(
const SupportedMotors & motor_type,
const std::string & joint_name,
const bool enable_dummy,
const AddressTable & table,
int baudrate,
uint8_t id,
double max_joint_limit,
double min_joint_limit,
std::shared_ptr< dynamixel::PortHandler > port_handler,
std::shared_ptr< dynamixel::PacketHandler > packet_handler
)
Construct a new Motor Base object.
Parameters:
- motor_type Type of the motor.
- joint_name Name of the joint which the motor is attaching to.
- enable_dummy If true, you can communicate with virtual dinamixel motor.
- table address table of the motor.
- baudrate Baudrate of the serial communication.
- id Id of the dynamixel motor.
- max_joint_limit
- min_joint_limit
- port_handler Port handler class of the dynamixel sdk.
- packet_handler Packet handler class of the dynamixel sdk
Template Parameters:
- AddressTable address table type of the motor.
Protected Functions Documentation#
function valueToTemperature#
virtual double valueToTemperature(
uint8_t value
) const
Reimplemented by: dynamixel_hardware_interface::motors::XW540_T260::valueToTemperature
function valueToTemperature#
virtual double valueToTemperature(
uint16_t value
) const
function valueToTemperature#
virtual double valueToTemperature(
uint32_t value
) const
function valueToRpm#
virtual double valueToRpm(
uint8_t value
) const
function valueToRpm#
virtual double valueToRpm(
uint16_t value
) const
function valueToRpm#
virtual double valueToRpm(
uint32_t value
) const
Reimplemented by: dynamixel_hardware_interface::motors::XW540_T260::valueToRpm
function rpmToVelocity#
inline void rpmToVelocity(
double rpm,
double & radian
) const
function radianToPosition#
template <typename T >
inline T radianToPosition(
double radian
) const
function radianToPosition#
uint16_t radianToPosition(
double radian
) const
function radianToPosition#
virtual void radianToPosition(
double radian,
uint8_t & value
) const
function radianToPosition#
virtual void radianToPosition(
double radian,
uint16_t & value
) const
function radianToPosition#
virtual void radianToPosition(
double radian,
uint32_t & value
) const
Reimplemented by: dynamixel_hardware_interface::motors::XW540_T260::radianToPosition
function positionToRadian#
virtual double positionToRadian(
const uint8_t position
) const
function positionToRadian#
virtual double positionToRadian(
const uint16_t position
) const
function positionToRadian#
virtual double positionToRadian(
const uint32_t position
) const
Reimplemented by: dynamixel_hardware_interface::motors::XW540_T260::positionToRadian
function getResult#
Result getResult(
int communication_result,
uint8_t packet_error
)
function MotorBase#
MotorBase()
Construct a new Motor Base object.
Public Attributes Documentation#
variable motor_type#
const SupportedMotors motor_type;
Describe the type of the motor.
variable min_joint_limit#
const double min_joint_limit;
variable max_joint_limit#
const double max_joint_limit;
variable joint_name#
const std::string joint_name;
Name of the joint which the motor is attaching to.
variable id#
const uint8_t id;
Id of the dynamixel motor.
variable enable_dummy#
const bool enable_dummy;
If true, you can communicate with virtual dinamixel motor.
variable baudrate#
const int baudrate;
Baudrate of the serial communication.
Protected Attributes Documentation#
variable present_temperature_#
double present_temperature_;
variable port_handler_#
std::shared_ptr< dynamixel::PortHandler > port_handler_;
variable packet_handler_#
std::shared_ptr< dynamixel::PacketHandler > packet_handler_;
variable joint_velocity_#
double joint_velocity_;
variable joint_position_#
double joint_position_;
variable goal_velocity_#
double goal_velocity_;
variable goal_position_#
double goal_position_;
variable address_table_#
std::shared_ptr< AddressTableBase > address_table_;
Updated on 17 July 2023 at 01:42:11 UTC