#include <roboteq.h>
Public Member Functions | |
void | doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) |
void | initialize () |
initialize the roboteq controller More... | |
void | initializeDiagnostic () |
void | initializeInterfaces (hardware_interface::JointStateInterface &joint_state_interface, hardware_interface::VelocityJointInterface &velocity_joint_interface) |
initializeInterfaces Initialize all motors. Add all Control Interface availbles and add in diagnostic task More... | |
bool | prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) |
void | read (const ros::Time &time, const ros::Duration &period) |
Roboteq (const ros::NodeHandle &nh, const ros::NodeHandle &private_nh, serial_controller *serial) | |
Roboteq The Roboteq board controller write and read messages about the motor state. More... | |
void | run (diagnostic_updater::DiagnosticStatusWrapper &stat) |
run Diagnostic thread called every request More... | |
void | updateDiagnostics () |
updateDiagnostics More... | |
void | write (const ros::Time &time, const ros::Duration &period) |
~Roboteq () | |
The deconstructor. More... | |
Public Member Functions inherited from hardware_interface::RobotHW | |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) |
RobotHW () | |
virtual | ~RobotHW () |
Public Member Functions inherited from hardware_interface::InterfaceManager | |
T * | get () |
std::vector< std::string > | getInterfaceResources (std::string iface_type) const |
std::vector< std::string > | getNames () const |
void | registerInterface (T *iface) |
void | registerInterfaceManager (InterfaceManager *iface_man) |
Public Member Functions inherited from diagnostic_updater::DiagnosticTask | |
DiagnosticTask (const std::string name) | |
const std::string & | getName () |
virtual | ~DiagnosticTask () |
Private Member Functions | |
void | connectionCallback (const ros::SingleSubscriberPublisher &pub) |
connectionCallback Check how many subscribers are connected More... | |
void | getControllerFromRoboteq () |
getPIDFromRoboteq Load PID parameters from Roboteq board More... | |
void | getRoboteqInformation () |
getRoboteqInformation Load basic information from roboteq board More... | |
void | reconfigureCBController (roboteq_control::RoboteqControllerConfig &config, uint32_t level) |
reconfigureCBEncoder when the dynamic reconfigurator change some values start this method More... | |
bool | service_Callback (roboteq_control::Service::Request &req, roboteq_control::Service::Response &msg_system) |
service_Callback Internal service to require information from the board connected More... | |
void | stop_Callback (const std_msgs::Bool::ConstPtr &msg) |
Additional Inherited Members | |
Protected Types inherited from hardware_interface::InterfaceManager | |
typedef std::vector< InterfaceManager * > | InterfaceManagerVector |
typedef std::map< std::string, void * > | InterfaceMap |
typedef std::map< std::string, std::vector< std::string > > | ResourceMap |
typedef std::map< std::string, size_t > | SizeMap |
Protected Attributes inherited from hardware_interface::InterfaceManager | |
boost::ptr_vector< ResourceManagerBase > | interface_destruction_list_ |
InterfaceManagerVector | interface_managers_ |
InterfaceMap | interfaces_ |
InterfaceMap | interfaces_combo_ |
SizeMap | num_ifaces_registered_ |
ResourceMap | resources_ |
roboteq::Roboteq::Roboteq | ( | const ros::NodeHandle & | nh, |
const ros::NodeHandle & | private_nh, | ||
serial_controller * | serial | ||
) |
Roboteq The Roboteq board controller write and read messages about the motor state.
nh | The ROS public node handle |
private_nh | the ROS private node handle |
serial | The serial controller |
Definition at line 37 of file roboteq.cpp.
roboteq::Roboteq::~Roboteq | ( | ) |
The deconstructor.
Definition at line 160 of file roboteq.cpp.
|
private |
connectionCallback Check how many subscribers are connected
pub | The information about the subscriber |
Definition at line 121 of file roboteq.cpp.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 491 of file roboteq.cpp.
|
private |
getPIDFromRoboteq Load PID parameters from Roboteq board
Definition at line 622 of file roboteq.cpp.
|
private |
getRoboteqInformation Load basic information from roboteq board
Definition at line 145 of file roboteq.cpp.
void roboteq::Roboteq::initialize | ( | ) |
initialize the roboteq controller
Definition at line 165 of file roboteq.cpp.
void roboteq::Roboteq::initializeDiagnostic | ( | ) |
Definition at line 254 of file roboteq.cpp.
void roboteq::Roboteq::initializeInterfaces | ( | hardware_interface::JointStateInterface & | joint_state_interface, |
hardware_interface::VelocityJointInterface & | velocity_joint_interface | ||
) |
initializeInterfaces Initialize all motors. Add all Control Interface availbles and add in diagnostic task
State interface
Velocity interface
Register interfaces
Definition at line 203 of file roboteq.cpp.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 485 of file roboteq.cpp.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 301 of file roboteq.cpp.
|
private |
reconfigureCBEncoder when the dynamic reconfigurator change some values start this method
config | variable with all configuration from dynamic reconfigurator |
level |
Definition at line 673 of file roboteq.cpp.
|
virtual |
run Diagnostic thread called every request
stat | the status of diagnostic updater |
Implements diagnostic_updater::DiagnosticTask.
Definition at line 541 of file roboteq.cpp.
|
private |
service_Callback Internal service to require information from the board connected
req | |
msg |
Definition at line 775 of file roboteq.cpp.
|
private |
Definition at line 128 of file roboteq.cpp.
void roboteq::Roboteq::updateDiagnostics | ( | ) |
updateDiagnostics
Definition at line 264 of file roboteq.cpp.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 473 of file roboteq.cpp.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |