Robotis Framework Packages
DYNAMIXEL SDK
Overview
DYNAMIXEL SDK is a standard programming libraries to develop the software that controls DYNAMIXEL. Please refer to the below link for more information about DYNAMIXEL SDK.
Reference : ROBOTIS DYNAMIXEL SDK Documents
Robotis Framework
robotis_controller
Overview
This is the main package that controls THORMANG3. This package is responsible for following functions.
- Initialization
- Load robot information file(.robot) and initialize the robot with the [[robotis_device]] package.
- Configures initial value for each joint by loading initialization file(.yaml).
- Gets ready to use sync write and bulk read for the joint control.
- Periodically call process() function by the timer (default cycle: 8 msec)
- The startTimer() creates a thread that calls process() function periodically.
- What process() does :
- Receives status packets with Bulk Read to get status of each sensors and joints.
- Transfers the result value of the Motion Module with Sync Write.
- Transfers instruction packet to each sensors and joints with Bulk Read.
- Calls process() function of the Sensor Module in the list and saves the result value.
- Calls process() function of the Motion Module in the list and saves the result value.
- Publishes current value and target value in the form of ROS Topic.
Please refer to the below link to create the Robot Manager that uses robotis_controller
package.
Reference : Creating new robot manager
ROS API
Subscribed Topics
/robotis/write_control_table
(robotis_controller_msgs/WriteControlTable)
The message can write multiple item values to a specific joint by using Sync Write.
/robotis/sync_write_item
(robotis_controller_msgs/SyncWriteItem)
The message can write a specific item value to multiple joints by using Sync Write.
/robotis/set_joint_ctrl_modules
(robotis_controller_msgs/JointCtrlModule)
The message can configure motion modules that controls specific joints.
/robotis/enable_ctrl_module
(std_msgs/String)
This message assigns a specific motion module that manages specific joints to a motion control module.
/robotis/set_control_mode
(std_msgs/String)
The message sets the control mode of robotis_controller
to ether DIRECT_CONTROL_MODE
or MOTION_MODULE_MODE
.
/robotis/set_joint_states
(sensor_msgs/JointState)
This message includes status data for each joint. The data in this message is transmitted to each joint to control the joint.
Published Topics
/robotis/goal_joint_states
(sensor_msgs/JointState)
The message publishes goal joint status value for each joint.
/robotis/present_joint_states
(sensor_msgs/JointState)
The message publishes current joint status value read from each joint.
/robotis/present_joint_ctrl_modules
(robotis_controller_msgs/JointCtrlModule)
The message publishes current status of motion module that controls each joint.
Services
/robotis/get_present_joint_ctrl_modules
(robotis_controller_msgs/GetJointModule)
The service to get the configuration of motion module that controls each joint.
robotis_device
Overview
This is the package that manages device information of ROBOTIS robots. This package is used when reading device information with the robot information file from the robotis_controller package.
Devices
The package is consisted of devices
folder that contains directories for each device and each device directory contains .device
file that saves device information. In order to add a new device, go to the relevant directory for the device and append the device information to the .device
file. The following is the content of each device file.
dynamixel
Device information file for dynamixel type is consisted of three sessions. The name of session is specified between ‘[’ and ‘]’. Comments start with ‘#’ and any texts after ‘#’ will not be considered as source code. The following is the option that can be configured in each session.
device info
[device info]
model_name = H54-200-S500-R
device_type = dynamixel
model_name
: Model name of the device.device_type
: Type of the device. Type can be eitherdynamixel
orsensor
.
type info
[type info]
torque_to_current_value_ratio = 9.09201
value_of_0_radian_position = 0
value_of_min_radian_position = -250950
value_of_max_radian_position = 250950
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_item_name = torque_enable
present_position_item_name = present_position
present_velocity_item_name = present_velocity
present_current_item_name = present_current
goal_position_item_name = goal_position
goal_velocity_item_name = goal_velocity
goal_current_item_name = goal_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
Values can be deleted for unused variables. However, depending on the control method, at least one goal_position_item_name or goal_velocity_item_name or goal_current_item_name should be defined.
torque_to_current_value_ratio
: The current ratio of torque to current control value.
current control value = torque(N) * torque_to_current_value_ratiovelocity_to_value_ratio
: The velocity ratio of velocity to control value.
velocity control value = velocity(Rad/s) * velocity_to_value_ratiomin_radian
: The minimum radian value of the position allowed for current dynamixel.max_radian
: The maximum radian value of the position allowed for current dynamixel.value_of_0_radian_position
: The position value at 0 radian position.value_of_min_radian_position
: The position value at min radian position.value_of_max_radian_position
: The position value at max radian position.torque_enable_item_name
: Name of the torque enable itempresent_position_item_name
: Name of the current position itempresent_velocity_item_name
: Name of the current velocity itempresent_current_item_name
: Name of the current current itemgoal_position_item_name
: Name of the goal position itemgoal_velocity_item_name
: Name of the goal velocity itemgoal_current_item_name
: Name of the goal current itemposition_d_gain_item_name
: Name of the D gain item of position PID controlposition_i_gain_item_name
: Name of the I gain item of position PID controlposition_p_gain_item_name
: Name of the P gain item of position PID control
control table
[control table]
# addr | item name | length | access | memory | min value | max value | signed
0 | model_number | 2 | R | EEPROM | 0 | 65535 | N
6 | version_of_firmware | 1 | R | EEPROM | 0 | 254 | N
7 | ID | 1 | RW | EEPROM | 0 | 252 | N
8 | baudrate | 1 | RW | EEPROM | 0 | 8 | N
...
address
: Address of the Item. When transmitting control packets, items in the control packet are distinguished by the address.item name
: Name of the Item. The item name is used to distinguish items in the topic for control.length
: Data length of the Item.access
: Access permission of the Item. (R:Read, W:Write, RW:Read/Write)memory
: Type of memory that saves the Item.EEPROM
: EEPROM keeps data without power supply. Some devices may not allow to write to EEPROM when torque is on.RAM
: RAM loses its data and become initialized when the power is cut off.
min value
: Minimum data value of the Item.max value
: Maximum data value of the Item.signed
: Y for signed Item data, N for unsigned Item data.
robotis_framework_common
Overview
The package contains commonly used Headers for the ROBOTIS Framework.
Description
singleton.h
Singleton pattern template
#ifndef ROBOTIS_FRAMEWORK_COMMON_SINGLETON_H_
#define ROBOTIS_FRAMEWORK_COMMON_SINGLETON_H_
namespace robotis_framework
{
template <class T>
class Singleton
{
private:
static T *unique_instance_;
protected:
Singleton() { }
Singleton(Singleton const&) { }
Singleton& operator=(Singleton const&) { return *this; }
public:
static T* getInstance()
{
if(unique_instance_ == NULL)
unique_instance_ = new T;
return unique_instance_;
}
static void destroyInstance()
{
if(unique_instance_)
{
delete unique_instance_;
unique_instance_ = NULL;
}
}
};
template <class T> T* Singleton<T>::unique_instance_ = NULL;
}
#endif /* ROBOTIS_FRAMEWORK_COMMON_SINGLETON_H_ */
motion_module.h
Please refer to the below link for the instruction of creating the new Motion Module.
Reference : Creating new motion module
sensor_module.h
Please refer to the below link for the instruction of creating the new Sensor Module.
Reference : Creating new sensor module
ROBOTIS Framework msgs
robotis_controller_msgs
Overview
This package defines Messages and Service that are used in the robotis_controller.