Go to the documentation of this file.
82 #ifndef DYNAMIXEL_INTERFACE_CONTROLLER_H_
83 #define DYNAMIXEL_INTERFACE_CONTROLLER_H_
96 #include <sensor_msgs/JointState.h>
100 #include <dynamixel_interface/DataPort.h>
101 #include <dynamixel_interface/DataPorts.h>
102 #include <dynamixel_interface/ServoDiag.h>
103 #include <dynamixel_interface/ServoDiags.h>
137 std::unique_ptr<DynamixelInterfaceDriver>
driver;
139 std::unordered_map<std::string, DynamixelInfo>
joints;
215 void multiThreadedIO(
PortInfo &port, sensor_msgs::JointState &read_msg, dynamixel_interface::DataPorts &dataport_msg,
216 dynamixel_interface::ServoDiags &status_msg,
bool perform_write)
const;
229 dynamixel_interface::DataPorts &dataports_msg,
230 dynamixel_interface::ServoDiags &diags_msg)
const;
232 std::unique_ptr<ros::NodeHandle>
nh_;
279 #endif // DYNAMIXEL_INTERFACE_CONTROLLER_H_
double torque_limit
Motor maximum torque limit (rated max)
int recv_queue_size_
Receive queue size for desired_joint_states topic.
const DynamixelSpec * model_spec
Motor model specification including encoder counts and unit conversion factors.
bool parseParameters(void)
bool write_ready_
Booleans indicating if we have received commands.
Struct that describes each servo's place in the system including which joint it corresponds to.
uint dataport_iters_
publish when dataport_counter_ == this
std::mutex write_mutex_
Mutex for write_msg, as there are potentially multiple threads.
DynamixelControlMode current_mode
control mode (position, velocity, torque)
void multiThreadedIO(PortInfo &port, sensor_msgs::JointState &read_msg, dynamixel_interface::DataPorts &dataport_msg, dynamixel_interface::ServoDiags &status_msg, bool perform_write) const
bool parameters_parsed_
method of control (position/velocity/torque)
Defines the hardware abstraction methods for communicating with dynamixels.
double diagnostics_rate_
Desired rate at which servo diagnostic information is published.
bool parseServoInformation(PortInfo &port, XmlRpc::XmlRpcValue servos)
void multiThreadedRead(PortInfo &port, sensor_msgs::JointState &read_msg, dynamixel_interface::DataPorts &dataports_msg, dynamixel_interface::ServoDiags &diags_msg) const
uint diagnostics_counter_
Counter for tracking diagnostics rate.
Struct which stores information about each port in use and which joints use that port.
bool initialiseDynamixel(PortInfo &port, DynamixelInfo &dynamixel)
uint dataport_counter_
counter for tracking dataport rate
Struct that describes the dynamixel motor's static and physical properties.
int max_pos
Motor maximum encoder value. Note that if min > max, the motor direction is reversed.
ros::Publisher joint_state_publisher_
Publishes joint states from reads.
double loop_rate_
Desired loop rate (joint states are published at this rate)
std::string port_name
User defined port name.
sensor_msgs::JointState write_msg_
Stores the last message received from the write command topic.
ros::Publisher diagnostics_publisher_
Publishes joint states from reads.
DynamixelControlMode control_type_
std::vector< PortInfo > dynamixel_ports_
method of control (position/velocity/torque)
bool ignore_input_velocity_
can set driver to ignore profile velocity commands in position mode
bool read_dataport_
Bool for telling threads to read dataport data.
int min_pos
Motor minimum encoder value. Note that if min > max, the motor direction is reversed.
~DynamixelInterfaceController()
Destructor, deletes the objects holding the serial ports and disables the motors if required.
bool read_diagnostics_
Bool for telling threads to read diagnostics data.
ros::Publisher debug_publisher_
Debug message publisher.
std::string joint_name
The unique (globally) name of the joint.
void multiThreadedWrite(PortInfo &port, sensor_msgs::JointState joint_commands) const
bool use_legacy_protocol
boolean indicating if legacy protocol (for older series dynamixels) is in use
int baudrate
Serial baud rate.
ros::Timer broadcast_timer_
Timer that controls the rate of the IO callback.
double dataport_rate_
Rate at which the pro external dataport is read.
double global_torque_limit_
global joint torque limit
DynamixelInterfaceController()
bool initialised_
Bool indicating if we are ready for operation.
std::unique_ptr< DynamixelInterfaceDriver > driver
The driver object.
ros::Publisher dataport_publisher_
Publishes the data from the external ports on dynamixel_pros.
ros::Subscriber joint_state_subscriber_
Gets joint states for writes.
void jointStateCallback(const sensor_msgs::JointState::ConstPtr &joint_commands)
double max_vel
Motor maximum joint velocity (rad/s)
bool parsePortInformation(XmlRpc::XmlRpcValue ports)
bool stop_motors_on_shutdown_
Indicates if the motors should be turned off when the controller stops.
uint diagnostics_iters_
publish when diagnostic_counter_ == this
bool initialisePort(PortInfo &port)
int id
The unique (per port) ID of the motor.
std::unordered_map< std::string, DynamixelInfo > joints
map of joint information by name
bool torque_enabled
Motor enable flag.
std::string device
Serial device name.
double global_max_vel_
global joint speed limit
int zero_pos
Motor initial position (in raw encoder values). This value defines the 0 radian position.
uint8_t hardware_status
current motor status, used for hardware error reporting
std::unique_ptr< ros::NodeHandle > nh_
Handler for the ROS Node.