Public Member Functions | Private Member Functions | Private Attributes | List of all members
roboteq::Roboteq Class Reference

#include <roboteq.h>

Inheritance diagram for roboteq::Roboteq:
Inheritance graph
[legend]

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::stringgetInterfaceResources (std::string iface_type) const
 
std::vector< std::stringgetNames () 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::stringgetName ()
 
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)
 

Private Attributes

status_fault_t _fault
 
bool _first
 ROS Control interfaces. More...
 
status_flag_t _flag
 
bool _isGPIOreading
 
roboteq_control::RoboteqControllerConfig _last_controller_config
 
string _model
 
std::vector< GPIOAnalogConfigurator * > _param_analog
 
std::vector< GPIOEncoderConfigurator * > _param_encoder
 
std::vector< GPIOPulseConfigurator * > _param_pulse
 
double _temp_bridge
 
double _temp_mcu
 
string _type
 
string _uid
 
string _version
 
double _volts_five
 
double _volts_internal
 
roboteq_control::RoboteqControllerConfig default_controller_config
 
diagnostic_updater::Updater diagnostic_updater
 
dynamic_reconfigure::Server< roboteq_control::RoboteqControllerConfig > * ds_controller
 Dynamic reconfigure PID. More...
 
bool first_read_ = true
 
double first_read_pos_ [2]
 
std::vector< Motor * > mMotor
 
ros::NodeHandle mNh
 
urdf::Model model
 URDF information about robot. More...
 
serial_controllermSerial
 
roboteq_control::Peripheral msg_peripheral
 
ros::NodeHandle private_mNh
 
ros::Publisher pub_peripheral
 
bool setup_controller
 Setup variable. More...
 
ros::ServiceServer srv_board
 
ros::Subscriber sub_stop
 

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< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

Definition at line 89 of file roboteq.h.

Constructor & Destructor Documentation

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.

Parameters
nhThe ROS public node handle
private_nhthe ROS private node handle
serialThe serial controller

Definition at line 37 of file roboteq.cpp.

roboteq::Roboteq::~Roboteq ( )

The deconstructor.

Definition at line 160 of file roboteq.cpp.

Member Function Documentation

void roboteq::Roboteq::connectionCallback ( const ros::SingleSubscriberPublisher pub)
private

connectionCallback Check how many subscribers are connected

Parameters
pubThe information about the subscriber

Definition at line 121 of file roboteq.cpp.

void roboteq::Roboteq::doSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 491 of file roboteq.cpp.

void roboteq::Roboteq::getControllerFromRoboteq ( )
private

getPIDFromRoboteq Load PID parameters from Roboteq board

Definition at line 622 of file roboteq.cpp.

void roboteq::Roboteq::getRoboteqInformation ( )
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.

bool roboteq::Roboteq::prepareSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 485 of file roboteq.cpp.

void roboteq::Roboteq::read ( const ros::Time time,
const ros::Duration period 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 301 of file roboteq.cpp.

void roboteq::Roboteq::reconfigureCBController ( roboteq_control::RoboteqControllerConfig &  config,
uint32_t  level 
)
private

reconfigureCBEncoder when the dynamic reconfigurator change some values start this method

Parameters
configvariable with all configuration from dynamic reconfigurator
level

Definition at line 673 of file roboteq.cpp.

void roboteq::Roboteq::run ( diagnostic_updater::DiagnosticStatusWrapper stat)
virtual

run Diagnostic thread called every request

Parameters
statthe status of diagnostic updater

Implements diagnostic_updater::DiagnosticTask.

Definition at line 541 of file roboteq.cpp.

bool roboteq::Roboteq::service_Callback ( roboteq_control::Service::Request &  req,
roboteq_control::Service::Response &  msg_system 
)
private

service_Callback Internal service to require information from the board connected

Parameters
req
msg
Returns

Definition at line 775 of file roboteq.cpp.

void roboteq::Roboteq::stop_Callback ( const std_msgs::Bool::ConstPtr &  msg)
private

Definition at line 128 of file roboteq.cpp.

void roboteq::Roboteq::updateDiagnostics ( )

updateDiagnostics

Definition at line 264 of file roboteq.cpp.

void roboteq::Roboteq::write ( const ros::Time time,
const ros::Duration period 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 473 of file roboteq.cpp.

Member Data Documentation

status_fault_t roboteq::Roboteq::_fault
private

Definition at line 168 of file roboteq.h.

bool roboteq::Roboteq::_first
private

ROS Control interfaces.

Definition at line 157 of file roboteq.h.

status_flag_t roboteq::Roboteq::_flag
private

Definition at line 166 of file roboteq.h.

bool roboteq::Roboteq::_isGPIOreading
private

Definition at line 178 of file roboteq.h.

roboteq_control::RoboteqControllerConfig roboteq::Roboteq::_last_controller_config
private

Definition at line 206 of file roboteq.h.

string roboteq::Roboteq::_model
private

Definition at line 162 of file roboteq.h.

std::vector<GPIOAnalogConfigurator*> roboteq::Roboteq::_param_analog
private

Definition at line 180 of file roboteq.h.

std::vector<GPIOEncoderConfigurator*> roboteq::Roboteq::_param_encoder
private

Definition at line 183 of file roboteq.h.

std::vector<GPIOPulseConfigurator*> roboteq::Roboteq::_param_pulse
private

Definition at line 181 of file roboteq.h.

double roboteq::Roboteq::_temp_bridge
private

Definition at line 172 of file roboteq.h.

double roboteq::Roboteq::_temp_mcu
private

Definition at line 172 of file roboteq.h.

string roboteq::Roboteq::_type
private

Definition at line 162 of file roboteq.h.

string roboteq::Roboteq::_uid
private

Definition at line 164 of file roboteq.h.

string roboteq::Roboteq::_version
private

Definition at line 163 of file roboteq.h.

double roboteq::Roboteq::_volts_five
private

Definition at line 170 of file roboteq.h.

double roboteq::Roboteq::_volts_internal
private

Definition at line 170 of file roboteq.h.

roboteq_control::RoboteqControllerConfig roboteq::Roboteq::default_controller_config
private

Definition at line 206 of file roboteq.h.

diagnostic_updater::Updater roboteq::Roboteq::diagnostic_updater
private

Definition at line 141 of file roboteq.h.

dynamic_reconfigure::Server<roboteq_control::RoboteqControllerConfig>* roboteq::Roboteq::ds_controller
private

Dynamic reconfigure PID.

Definition at line 197 of file roboteq.h.

bool roboteq::Roboteq::first_read_ = true
private

Definition at line 174 of file roboteq.h.

double roboteq::Roboteq::first_read_pos_[2]
private

Definition at line 175 of file roboteq.h.

std::vector<Motor*> roboteq::Roboteq::mMotor
private

Definition at line 160 of file roboteq.h.

ros::NodeHandle roboteq::Roboteq::mNh
private

Definition at line 136 of file roboteq.h.

urdf::Model roboteq::Roboteq::model
private

URDF information about robot.

Definition at line 150 of file roboteq.h.

serial_controller* roboteq::Roboteq::mSerial
private

Definition at line 139 of file roboteq.h.

roboteq_control::Peripheral roboteq::Roboteq::msg_peripheral
private

Definition at line 179 of file roboteq.h.

ros::NodeHandle roboteq::Roboteq::private_mNh
private

Definition at line 137 of file roboteq.h.

ros::Publisher roboteq::Roboteq::pub_peripheral
private

Definition at line 143 of file roboteq.h.

bool roboteq::Roboteq::setup_controller
private

Setup variable.

Definition at line 194 of file roboteq.h.

ros::ServiceServer roboteq::Roboteq::srv_board
private

Definition at line 147 of file roboteq.h.

ros::Subscriber roboteq::Roboteq::sub_stop
private

Definition at line 145 of file roboteq.h.


The documentation for this class was generated from the following files:


roboteq_control
Author(s): Raffaello Bonghi
autogenerated on Wed Jan 3 2018 03:48:23