Public Member Functions | Public Attributes | Protected Member Functions | Static Protected Member Functions | Private Member Functions | Private Attributes | List of all members
roboteq::Motor Class Reference

#include <motor.h>

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

Public Member Functions

string getName ()
 getName the name of the motor More...
 
int getNumber ()
 getNumber The roboteq number More...
 
void initializeMotor (bool load_from_board)
 initializeMotor Initialization oh motor, this routine load parameter from ros server or load from roboteq board More...
 
 Motor (const ros::NodeHandle &nh, serial_controller *serial, string name, unsigned int number)
 Motor The motor definition and all ros controller initializations are collected in this place. More...
 
void readVector (std::vector< std::string > fields)
 readVector Decode vector data list More...
 
void registerSensor (GPIOSensor *sensor)
 registerSensor register the sensor More...
 
void resetPosition (double position)
 resetPosition Reset the motor in a new initial position More...
 
void run (diagnostic_updater::DiagnosticStatusWrapper &stat)
 run Run the diagnostic updater More...
 
void setupLimits (urdf::Model model)
 setupLimits setup the maximum velocity, positio and effort More...
 
void stopMotor ()
 stopMotor Stop the motor More...
 
void switchController (string type)
 switchController Switch the controller from different type of ros controller More...
 
void writeCommandsToHardware (ros::Duration period)
 writeCommandsToHardware Write a command to the hardware interface More...
 
- Public Member Functions inherited from diagnostic_updater::DiagnosticTask
 DiagnosticTask (const std::string name)
 
const std::stringgetName ()
 
virtual ~DiagnosticTask ()
 

Public Attributes

hardware_interface::JointHandle joint_handle
 
hardware_interface::JointStateHandle joint_state_handle
 
unsigned int mNumber
 
double position
 

Protected Member Functions

double from_encoder_ticks (double x)
 
double to_encoder_ticks (double x)
 

Static Protected Member Functions

static double from_rpm (double x)
 
static double to_rpm (double x)
 

Private Member Functions

void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
void read (string data)
 

Private Attributes

int _control_mode
 
GPIOSensor_sensor
 
motor_status_t _status
 
double command
 
double effort
 
double max_effort
 
double max_position
 
double max_velocity
 
string mMotorName
 
ros::NodeHandle mNh
 
serial_controllermSerial
 
roboteq_control::ControlStatus msg_control
 
roboteq_control::MotorStatus msg_status
 
MotorParamConfiguratorparameter
 
MotorPIDConfiguratorpid_position
 
MotorPIDConfiguratorpid_torque
 
MotorPIDConfiguratorpid_velocity
 
ros::Publisher pub_control
 
ros::Publisher pub_status
 
joint_limits_interface::VelocityJointSoftLimitsInterface vel_limits_interface
 ROS joint limits interface. More...
 
double velocity
 

Detailed Description

Definition at line 65 of file motor.h.

Constructor & Destructor Documentation

roboteq::Motor::Motor ( const ros::NodeHandle nh,
serial_controller serial,
string  name,
unsigned int  number 
)
explicit

Motor The motor definition and all ros controller initializations are collected in this place.

Parameters
nhThe ROS private node handle
serialThe serial controller
nameThe name of the motor
numberThe number in Roboteq board

Definition at line 41 of file motor.cpp.

Member Function Documentation

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

Definition at line 74 of file motor.cpp.

double roboteq::Motor::from_encoder_ticks ( double  x)
protected

Conversion of encoder ticks to radians.

Parameters
xAngular position in encoder ticks.
Returns
Angular position in radians.

Definition at line 128 of file motor.cpp.

static double roboteq::Motor::from_rpm ( double  x)
inlinestaticprotected
Parameters
xAngular velocity in RPM.
Returns
Angular velocity in rad/s.

Definition at line 158 of file motor.h.

string roboteq::Motor::getName ( )
inline

getName the name of the motor

Returns
the string with the name of the motor

Definition at line 122 of file motor.h.

int roboteq::Motor::getNumber ( )
inline

getNumber The roboteq number

Returns
the number associated in the roboteq board

Definition at line 114 of file motor.h.

void roboteq::Motor::initializeMotor ( bool  load_from_board)

initializeMotor Initialization oh motor, this routine load parameter from ros server or load from roboteq board

Parameters
load_from_boardforse the load from roboteq board

Definition at line 79 of file motor.cpp.

void roboteq::Motor::read ( string  data)
private

Definition at line 350 of file motor.cpp.

void roboteq::Motor::readVector ( std::vector< std::string fields)

readVector Decode vector data list

Parameters
fieldsfield of measures

Definition at line 357 of file motor.cpp.

void roboteq::Motor::registerSensor ( GPIOSensor sensor)
inline

registerSensor register the sensor

Parameters
sensorthe sensor interface

Definition at line 129 of file motor.h.

void roboteq::Motor::resetPosition ( double  position)

resetPosition Reset the motor in a new initial position

Parameters
positionthe new position

Definition at line 326 of file motor.cpp.

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

run Run the diagnostic updater

Parameters
statthe stat will be updated

Implements diagnostic_updater::DiagnosticTask.

Definition at line 211 of file motor.cpp.

void roboteq::Motor::setupLimits ( urdf::Model  model)

setupLimits setup the maximum velocity, positio and effort

Parameters
modelthe robot model

Add a velocity joint limits infomations

Definition at line 140 of file motor.cpp.

void roboteq::Motor::stopMotor ( )

stopMotor Stop the motor

Definition at line 298 of file motor.cpp.

void roboteq::Motor::switchController ( string  type)

switchController Switch the controller from different type of ros controller

Parameters
typethe type of ros controller

Definition at line 306 of file motor.cpp.

double roboteq::Motor::to_encoder_ticks ( double  x)
protected

Conversion of radians to encoder ticks.

Parameters
xAngular position in radians.
Returns
Angular position in encoder ticks.

Definition at line 109 of file motor.cpp.

static double roboteq::Motor::to_rpm ( double  x)
inlinestaticprotected
Parameters
xAngular velocity in radians/s.
Returns
Angular velocity in RPM.

Definition at line 149 of file motor.h.

void roboteq::Motor::writeCommandsToHardware ( ros::Duration  period)

writeCommandsToHardware Write a command to the hardware interface

Parameters
periodthe period update

Definition at line 334 of file motor.cpp.

Member Data Documentation

int roboteq::Motor::_control_mode
private

Definition at line 195 of file motor.h.

GPIOSensor* roboteq::Motor::_sensor
private

Definition at line 212 of file motor.h.

motor_status_t roboteq::Motor::_status
private

Definition at line 196 of file motor.h.

double roboteq::Motor::command
private

Definition at line 193 of file motor.h.

double roboteq::Motor::effort
private

Definition at line 192 of file motor.h.

hardware_interface::JointHandle roboteq::Motor::joint_handle

Definition at line 140 of file motor.h.

hardware_interface::JointStateHandle roboteq::Motor::joint_state_handle

Definition at line 139 of file motor.h.

double roboteq::Motor::max_effort
private

Definition at line 192 of file motor.h.

double roboteq::Motor::max_position
private

Definition at line 190 of file motor.h.

double roboteq::Motor::max_velocity
private

Definition at line 191 of file motor.h.

string roboteq::Motor::mMotorName
private

Definition at line 186 of file motor.h.

ros::NodeHandle roboteq::Motor::mNh
private

Definition at line 184 of file motor.h.

unsigned int roboteq::Motor::mNumber

Definition at line 143 of file motor.h.

serial_controller* roboteq::Motor::mSerial
private

Definition at line 188 of file motor.h.

roboteq_control::ControlStatus roboteq::Motor::msg_control
private

Definition at line 205 of file motor.h.

roboteq_control::MotorStatus roboteq::Motor::msg_status
private

Definition at line 204 of file motor.h.

MotorParamConfigurator* roboteq::Motor::parameter
private

Definition at line 207 of file motor.h.

MotorPIDConfigurator* roboteq::Motor::pid_position
private

Definition at line 210 of file motor.h.

MotorPIDConfigurator* roboteq::Motor::pid_torque
private

Definition at line 209 of file motor.h.

MotorPIDConfigurator* roboteq::Motor::pid_velocity
private

Definition at line 208 of file motor.h.

double roboteq::Motor::position

Definition at line 179 of file motor.h.

ros::Publisher roboteq::Motor::pub_control
private

Definition at line 202 of file motor.h.

ros::Publisher roboteq::Motor::pub_status
private

Definition at line 202 of file motor.h.

joint_limits_interface::VelocityJointSoftLimitsInterface roboteq::Motor::vel_limits_interface
private

ROS joint limits interface.

Definition at line 199 of file motor.h.

double roboteq::Motor::velocity
private

Definition at line 191 of file motor.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