dynamixel_hardware_interface::motors::XW540_T260#
Inherits from dynamixel_hardware_interface::MotorBase
Public Functions#
Name | |
---|---|
virtual double | valueToTemperature(uint8_t value) const override |
virtual double | valueToRpm(uint32_t value) const override |
virtual void | radianToPosition(double radian, uint32_t & value) const override |
virtual double | positionToRadian(const uint32_t position) const override |
XW540_T260(const std::string joint_name, bool enable_dummy, 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) |
Additional inherited members#
Public Functions inherited from dynamixel_hardware_interface::MotorBase
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. |
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 inherited from dynamixel_hardware_interface::MotorBase
Name | |
---|---|
void | rpmToVelocity(double rpm, double & radian) const |
Result | getResult(int communication_result, uint8_t packet_error) |
MotorBase() Construct a new Motor Base object. |
Public Attributes inherited from dynamixel_hardware_interface::MotorBase
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 inherited from dynamixel_hardware_interface::MotorBase
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 valueToTemperature#
inline virtual double valueToTemperature(
uint8_t value
) const override
Reimplements: dynamixel_hardware_interface::MotorBase::valueToTemperature
function valueToRpm#
inline virtual double valueToRpm(
uint32_t value
) const override
Reimplements: dynamixel_hardware_interface::MotorBase::valueToRpm
function radianToPosition#
inline virtual void radianToPosition(
double radian,
uint32_t & value
) const override
Reimplements: dynamixel_hardware_interface::MotorBase::radianToPosition
function positionToRadian#
inline virtual double positionToRadian(
const uint32_t position
) const override
Reimplements: dynamixel_hardware_interface::MotorBase::positionToRadian
function XW540_T260#
inline explicit XW540_T260(
const std::string joint_name,
bool enable_dummy,
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
)
Updated on 17 July 2023 at 01:42:10 UTC