#include <motor.h>
Definition at line 65 of file motor.h.
Motor The motor definition and all ros controller initializations are collected in this place.
- Parameters
-
nh | The ROS private node handle |
serial | The serial controller |
name | The name of the motor |
number | The number in Roboteq board |
Definition at line 41 of file motor.cpp.
double roboteq::Motor::from_encoder_ticks |
( |
double |
x | ) |
|
|
protected |
Conversion of encoder ticks to radians.
- Parameters
-
x | Angular 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
-
x | Angular 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_board | forse the load from roboteq board |
Definition at line 79 of file motor.cpp.
void roboteq::Motor::read |
( |
string |
data | ) |
|
|
private |
void roboteq::Motor::readVector |
( |
std::vector< std::string > |
fields | ) |
|
readVector Decode vector data list
- Parameters
-
Definition at line 357 of file motor.cpp.
void roboteq::Motor::registerSensor |
( |
GPIOSensor * |
sensor | ) |
|
|
inline |
registerSensor register the sensor
- Parameters
-
sensor | the 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
-
Definition at line 326 of file motor.cpp.
setupLimits setup the maximum velocity, positio and effort
- Parameters
-
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
-
type | the 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
-
x | Angular 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
-
x | Angular 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
-
Definition at line 334 of file motor.cpp.
int roboteq::Motor::_control_mode |
|
private |
double roboteq::Motor::command |
|
private |
double roboteq::Motor::effort |
|
private |
double roboteq::Motor::max_effort |
|
private |
double roboteq::Motor::max_position |
|
private |
double roboteq::Motor::max_velocity |
|
private |
string roboteq::Motor::mMotorName |
|
private |
unsigned int roboteq::Motor::mNumber |
roboteq_control::ControlStatus roboteq::Motor::msg_control |
|
private |
roboteq_control::MotorStatus roboteq::Motor::msg_status |
|
private |
double roboteq::Motor::position |
ROS joint limits interface.
Definition at line 199 of file motor.h.
double roboteq::Motor::velocity |
|
private |
The documentation for this class was generated from the following files: