#include <RobChair.h>
Public Types | |
| enum | _CommonFunction { TurnOff = 0, TurnOn = 1 } |
| Common functions. More... | |
| enum | _EncoderFunction { SetVelocityValue = 2, SetEncoderControlMode = 3, SetPIControlValues = 4, ResetEncoderInformation = 5, DataFromEncoder = 6 } |
| Encoder functions. More... | |
| enum | _PDriveFunction { SetDACCommand = 2, SetPDriveControlMode = 3, DataFromMotor = 4 } |
| PDrive functions. More... | |
| enum | _RobChairDS { PC = 0, RightPDrive = 1, LeftPDrive = 2, BothPDrives = 3, RightEncoder = 4, LeftEncoder = 5, BothEncoders = 6, Joystick = 10, SyncMCU = 15 } |
| RobChair destinations and sources. More... | |
| enum | _TriggerFunction { SyncronizeAllNodes = 15 } |
| Trigger functions. More... | |
| typedef enum RobChair::_CommonFunction | CommonFunction |
| Common functions. | |
| typedef enum RobChair::_EncoderFunction | EncoderFunction |
| Encoder functions. | |
| typedef enum RobChair::_PDriveFunction | PDriveFunction |
| PDrive functions. | |
| typedef enum RobChair::_RobChairDS | RobChairDS |
| RobChair destinations and sources. | |
| typedef enum RobChair::_TriggerFunction | TriggerFunction |
| Trigger functions. | |
Public Member Functions | |
| double | getAngularVelocity () |
| Getter for the robot angular velocity. | |
| double | getLinearVelocity () |
| Getter for the robot linear velocity. | |
| double | getPositionX () |
| Getter for the robot x position. | |
| double | getPositionY () |
| Getter for the robot y position. | |
| double | getYaw () |
| void | initializeRobChair (ros::Publisher *can_pub, double kp=0.0, double ki=0.0) |
| This function initializes the PDrives, the Encoders and the Trigger in the RobChair robot. | |
| void | receivedCANFrame (const can_msgs::CANFrame::ConstPtr &msg) |
| Callback for incoming CAN frames. | |
| void | resetEncoders () |
| This function resets both encoders. | |
| RobChair () | |
| RobChair constructor. This is the class constructor. | |
| void | setPIControlValues (RobChairDS destination, double kp, double ki) |
| This function allows to set the PID control gains for the RobChair speed controller. | |
| void | setVelocities (double linear_velocity, double angular_velocity) |
| This function allows to send velocity commands to the velocity controllers. | |
| ~RobChair () | |
| RobChair destructor. | |
Private Member Functions | |
| void | decodeEncoderData (RobChairDS encoder, const can_msgs::CANFrame::ConstPtr &msg) |
| This function decodes the data sent from the encoders to the PC. | |
| double | limitAngle (double angle) |
| The angles must be contained between [-Pi, Pi]. | |
| void | sendCANFrame (RobChairDS destination, char function, char *data, int data_count, char n=0) |
| This functions sends CAN frames to the RobChair CAN bus. | |
| void | setVelocity (RobChairDS destination, double velocity) |
| This function allows to set the velocity reference on the RobChair motor drivers. | |
| void | turnEncodersOff () |
| This functions turns the Encoders on the RobChair OFF - Idle Mode. | |
| void | turnEncodersOn () |
| This functions turns the Encoders on the RobChair ON - Running Mode. | |
| void | turnPDrivesOff () |
| This functions turns the PDrives on the RobChair OFF - Idle Mode. | |
| void | turnPDrivesOn () |
| This functions turns the PDrives on the RobChair ON - Running Mode. | |
| void | turnTriggerOff () |
| This functions turns the Trigger on the RobChair OFF - Running Mode. | |
| void | turnTriggerOn () |
| This functions turns the Trigger on the RobChair ON - Running Mode. | |
Private Attributes | |
| double | angular_velocity_ |
| Angular velocity. | |
| ros::Publisher * | can_pub_ |
| CANopen bus ROS publisher. | |
| bool | got_left_encoder_data_ |
| Flag for left encoder data. | |
| bool | got_right_encoder_data_ |
| Flag for right encoder data. | |
| double | last_left_wheel_position_ |
| The last left wheel position. | |
| double | last_right_wheel_position_ |
| The last right wheel position. | |
| double | left_wheel_position_ |
| Left wheel position. | |
| double | left_wheel_velocity_ |
| Left wheel velocity. | |
| double | linear_velocity_ |
| Velocity in x. | |
| char | n_ |
| Current time slot sent by the trigger. | |
| double | right_wheel_position_ |
| Right wheel position. | |
| double | right_wheel_velocity_ |
| Right wheel velocity. | |
| double | x_ |
| Position in x. | |
| double | y_ |
| Position in y. | |
| double | yaw_ |
| Yaw. | |
Definition at line 57 of file RobChair.h.
| typedef enum RobChair::_CommonFunction RobChair::CommonFunction |
Common functions.
| typedef enum RobChair::_EncoderFunction RobChair::EncoderFunction |
Encoder functions.
| typedef enum RobChair::_PDriveFunction RobChair::PDriveFunction |
PDrive functions.
| typedef enum RobChair::_RobChairDS RobChair::RobChairDS |
RobChair destinations and sources.
| typedef enum RobChair::_TriggerFunction RobChair::TriggerFunction |
Trigger functions.
Encoder functions.
| SetVelocityValue | |
| SetEncoderControlMode | |
| SetPIControlValues | |
| ResetEncoderInformation | |
| DataFromEncoder |
Definition at line 94 of file RobChair.h.
PDrive functions.
Definition at line 85 of file RobChair.h.
RobChair destinations and sources.
| PC | |
| RightPDrive | |
| LeftPDrive | |
| BothPDrives | |
| RightEncoder | |
| LeftEncoder | |
| BothEncoders | |
| Joystick | |
| SyncMCU |
Definition at line 62 of file RobChair.h.
RobChair constructor. This is the class constructor.
Definition at line 40 of file RobChair.cpp.
| void RobChair::decodeEncoderData | ( | RobChairDS | encoder, |
| const can_msgs::CANFrame::ConstPtr & | msg | ||
| ) | [private] |
This function decodes the data sent from the encoders to the PC.
| encoder | The source of the data, valid values are LeftEncoder and RightEncoder. |
| msg | The data to be decoded. |
Definition at line 121 of file RobChair.cpp.
| double RobChair::getAngularVelocity | ( | ) | [inline] |
Getter for the robot angular velocity.
Definition at line 213 of file RobChair.h.
| double RobChair::getLinearVelocity | ( | ) | [inline] |
Getter for the robot linear velocity.
Definition at line 205 of file RobChair.h.
| double RobChair::getPositionX | ( | ) | [inline] |
Getter for the robot x position.
Definition at line 181 of file RobChair.h.
| double RobChair::getPositionY | ( | ) | [inline] |
Getter for the robot y position.
Definition at line 189 of file RobChair.h.
| double RobChair::getYaw | ( | ) | [inline] |
Definition at line 197 of file RobChair.h.
| void RobChair::initializeRobChair | ( | ros::Publisher * | can_pub, |
| double | kp = 0.0, |
||
| double | ki = 0.0 |
||
| ) |
This function initializes the PDrives, the Encoders and the Trigger in the RobChair robot.
| can_pub | The ROS publisher for the CAN topic. |
| kp | The proportional gain of the speed controller. |
| ki | The integral gain of the speed controller. |
Definition at line 53 of file RobChair.cpp.
| double RobChair::limitAngle | ( | double | angle | ) | [private] |
The angles must be contained between [-Pi, Pi].
| angle | The angle to be limited. |
Definition at line 240 of file RobChair.cpp.
| void RobChair::receivedCANFrame | ( | const can_msgs::CANFrame::ConstPtr & | frame_msg | ) |
Callback for incoming CAN frames.
| msg | The incoming CAN frame. |
Definition at line 196 of file RobChair.cpp.
| void RobChair::resetEncoders | ( | ) | [inline] |
This function resets both encoders.
Definition at line 163 of file RobChair.h.
| void RobChair::sendCANFrame | ( | RobChairDS | destination, |
| char | function, | ||
| char * | data, | ||
| int | data_count, | ||
| char | n = 0 |
||
| ) | [private] |
This functions sends CAN frames to the RobChair CAN bus.
| destination | The destination device RobChairDS. |
| function | The desired function, PDriveFunction, EncoderFunction or TriggerFunction. |
| data | The data to be sent. |
| data_count | The number of bytes to be sent. |
| n | The trigger time slot to send the frame. |
Definition at line 170 of file RobChair.cpp.
| void RobChair::setPIControlValues | ( | RobChairDS | destination, |
| double | kp, | ||
| double | ki | ||
| ) |
This function allows to set the PID control gains for the RobChair speed controller.
| destination | The destination PDrive, accepted values are LeftPDrive, RightPDrive and BothPDrives. |
| kp | The proportional gain of the speed controller. |
| ki | The integral gain of the speed controller. |
Definition at line 85 of file RobChair.cpp.
| void RobChair::setVelocities | ( | double | linear_velocity, |
| double | angular_velocity | ||
| ) |
This function allows to send velocity commands to the velocity controllers.
| linear_velocity | Linear velocity to the robot in m/s. |
| angular_velocity | Angular velocity to the robot in m/s. |
Definition at line 99 of file RobChair.cpp.
| void RobChair::setVelocity | ( | RobChairDS | destination, |
| double | velocity | ||
| ) | [private] |
This function allows to set the velocity reference on the RobChair motor drivers.
| destination | The destination device RobChairDS, valid values are LeftEncoder, RightEncoder and BothEncoders. |
| velocity | The reference velocity to the controller. |
| void RobChair::turnEncodersOff | ( | ) | [inline, private] |
This functions turns the Encoders on the RobChair OFF - Idle Mode.
Definition at line 279 of file RobChair.h.
| void RobChair::turnEncodersOn | ( | ) | [inline, private] |
This functions turns the Encoders on the RobChair ON - Running Mode.
Definition at line 272 of file RobChair.h.
| void RobChair::turnPDrivesOff | ( | ) | [inline, private] |
This functions turns the PDrives on the RobChair OFF - Idle Mode.
Definition at line 264 of file RobChair.h.
| void RobChair::turnPDrivesOn | ( | ) | [inline, private] |
This functions turns the PDrives on the RobChair ON - Running Mode.
Definition at line 257 of file RobChair.h.
| void RobChair::turnTriggerOff | ( | ) | [inline, private] |
This functions turns the Trigger on the RobChair OFF - Running Mode.
Definition at line 294 of file RobChair.h.
| void RobChair::turnTriggerOn | ( | ) | [inline, private] |
This functions turns the Trigger on the RobChair ON - Running Mode.
Definition at line 287 of file RobChair.h.
double RobChair::angular_velocity_ [private] |
Angular velocity.
Definition at line 313 of file RobChair.h.
ros::Publisher* RobChair::can_pub_ [private] |
CANopen bus ROS publisher.
Definition at line 298 of file RobChair.h.
bool RobChair::got_left_encoder_data_ [private] |
Flag for left encoder data.
Definition at line 330 of file RobChair.h.
bool RobChair::got_right_encoder_data_ [private] |
Flag for right encoder data.
Definition at line 332 of file RobChair.h.
double RobChair::last_left_wheel_position_ [private] |
The last left wheel position.
Definition at line 326 of file RobChair.h.
double RobChair::last_right_wheel_position_ [private] |
The last right wheel position.
Definition at line 328 of file RobChair.h.
double RobChair::left_wheel_position_ [private] |
Left wheel position.
Definition at line 316 of file RobChair.h.
double RobChair::left_wheel_velocity_ [private] |
Left wheel velocity.
Definition at line 318 of file RobChair.h.
double RobChair::linear_velocity_ [private] |
Velocity in x.
Definition at line 311 of file RobChair.h.
char RobChair::n_ [private] |
Current time slot sent by the trigger.
Definition at line 301 of file RobChair.h.
double RobChair::right_wheel_position_ [private] |
Right wheel position.
Definition at line 320 of file RobChair.h.
double RobChair::right_wheel_velocity_ [private] |
Right wheel velocity.
Definition at line 322 of file RobChair.h.
double RobChair::x_ [private] |
Position in x.
Definition at line 305 of file RobChair.h.
double RobChair::y_ [private] |
Position in y.
Definition at line 307 of file RobChair.h.
double RobChair::yaw_ [private] |
Yaw.
Definition at line 309 of file RobChair.h.