PX4 Firmware
PX4 Autopilot Software http://px4.io
|
This is a driver for the RoboClaw motor controller. More...
#include <RoboClaw.hpp>
Public Types | |
enum | e_channel { CH_VOLTAGE_LEFT = 0, CH_VOLTAGE_RIGHT } |
control channels More... | |
enum | e_motor { MOTOR_1 = 0, MOTOR_2 } |
motors More... | |
Public Member Functions | |
void | taskMain () |
RoboClaw (const char *deviceName, const char *baudRateParam) | |
constructor More... | |
virtual | ~RoboClaw () |
deconstructor More... | |
float | getMotorPosition (e_motor motor) |
float | getMotorSpeed (e_motor motor) |
int | setMotorSpeed (e_motor motor, float value) |
set the speed of a motor, rev/sec More... | |
int | setMotorDutyCycle (e_motor motor, float value) |
set the duty cycle of a motor More... | |
int | drive (float value) |
Drive both motors. More... | |
int | turn (float value) |
Turn. More... | |
int | resetEncoders () |
reset the encoders More... | |
int | readEncoder () |
read data from serial More... | |
void | printStatus (char *string, size_t n) |
print status More... | |
Static Public Attributes | |
static bool | taskShouldExit = false |
Private Types | |
enum | e_command { CMD_DRIVE_FWD_1 = 0, CMD_DRIVE_REV_1 = 1, CMD_DRIVE_FWD_2 = 4, CMD_DRIVE_REV_2 = 5, CMD_DRIVE_FWD_MIX = 8, CMD_DRIVE_REV_MIX = 9, CMD_TURN_RIGHT = 10, CMD_TURN_LEFT = 11, CMD_READ_ENCODER_1 = 16, CMD_READ_ENCODER_2 = 17, CMD_READ_SPEED_1 = 18, CMD_READ_SPEED_2 = 19, CMD_RESET_ENCODERS = 20, CMD_READ_BOTH_ENCODERS = 78, CMD_READ_BOTH_SPEEDS = 79, CMD_READ_SPEED_HIRES_1 = 30, CMD_READ_SPEED_HIRES_2 = 31, CMD_SIGNED_DUTYCYCLE_1 = 32, CMD_SIGNED_DUTYCYCLE_2 = 33, CMD_READ_STATUS = 90 } |
Private Member Functions | |
void | _parameters_update () |
int | _sendUnsigned7Bit (e_command command, float data) |
int | _sendSigned16Bit (e_command command, float data) |
int | _sendNothing (e_command) |
int | _transaction (e_command cmd, uint8_t *wbuff, size_t wbytes, uint8_t *rbuff, size_t rbytes, bool send_checksum=true, bool recv_checksum=false) |
Perform a round-trip write and read. More... | |
Static Private Member Functions | |
static uint16_t | _calcCRC (const uint8_t *buf, size_t n, uint16_t init=0) |
Private Attributes | |
struct { | |
speed_t serial_baud_rate | |
int32_t counts_per_rev | |
int32_t encoder_read_period_ms | |
int32_t actuator_write_period_ms | |
int32_t address | |
} | _parameters |
struct { | |
param_t serial_baud_rate | |
param_t counts_per_rev | |
param_t encoder_read_period_ms | |
param_t actuator_write_period_ms | |
param_t address | |
} | _param_handles |
int | _uart |
fd_set | _uart_set |
struct timeval | _uart_timeout |
int | _actuatorsSub {-1} |
actuator controls subscription More... | |
actuator_controls_s | _actuatorControls |
int | _armedSub {-1} |
actuator_armed_s | _actuatorArmed |
int | _paramSub {-1} |
parameter_update_s | _paramUpdate |
orb_advert_t | _wheelEncodersAdv [2] {nullptr, nullptr} |
wheel_encoders_s | _wheelEncoderMsg [2] |
uint32_t | _lastEncoderCount [2] {0, 0} |
int64_t | _encoderCounts [2] {0, 0} |
int32_t | _motorSpeeds [2] {0, 0} |
This is a driver for the RoboClaw motor controller.
Definition at line 62 of file RoboClaw.hpp.
enum RoboClaw::e_channel |
control channels
Enumerator | |
---|---|
CH_VOLTAGE_LEFT | |
CH_VOLTAGE_RIGHT |
Definition at line 70 of file RoboClaw.hpp.
|
private |
Definition at line 146 of file RoboClaw.hpp.
enum RoboClaw::e_motor |
RoboClaw::RoboClaw | ( | const char * | deviceName, |
const char * | baudRateParam | ||
) |
constructor
deviceName | the name of the serial port e.g. "/dev/ttyS2" |
address | the adddress of the motor (selectable on roboclaw) |
baudRateParam | Name of the parameter that holds the baud rate of this serial port |
Definition at line 80 of file RoboClaw.cpp.
References _actuatorsSub, _encoderCounts, _lastEncoderCount, _motorSpeeds, _param_handles, _parameters, _parameters_update(), _uart, _uart_set, err, param_find(), resetEncoders(), and TIMEOUT_US.
|
virtual |
deconstructor
Definition at line 128 of file RoboClaw.cpp.
References _uart, MOTOR_1, MOTOR_2, and setMotorDutyCycle().
|
staticprivate |
Definition at line 456 of file RoboClaw.cpp.
References ToneAlarmInterface::init().
Referenced by _transaction().
|
private |
Definition at line 569 of file RoboClaw.cpp.
References _actuatorsSub, _param_handles, _parameters, B460800, orb_set_interval(), and param_get().
Referenced by RoboClaw(), and taskMain().
|
private |
Definition at line 450 of file RoboClaw.cpp.
References _transaction().
Referenced by resetEncoders().
|
private |
Definition at line 436 of file RoboClaw.cpp.
References _transaction(), and f().
Referenced by setMotorDutyCycle().
|
private |
Definition at line 423 of file RoboClaw.cpp.
References _transaction(), and f().
Referenced by drive(), setMotorSpeed(), and turn().
|
private |
Perform a round-trip write and read.
NOTE: This function is not thread-safe.
cmd | Command to send to the Roboclaw |
wbuff | Write buffer. Must not contain command, address, or checksum. For most commands, this will be one or two bytes. Can be null iff wbytes == 0. |
wbytes | Number of bytes to write. Can be 0. |
rbuff | Read buffer. Will be filled with the entire response, including a checksum if the Roboclaw sends a checksum for this command. |
rbytes | Maximum number of bytes to read. |
send_checksum | If true, then the checksum will be calculated and sent to the Roboclaw. This is an option because some Roboclaw commands expect no checksum. |
recv_checksum | If true, then this function will calculate the checksum of the returned data and compare it to the checksum received. If they are not equal, OR if fewer than 2 bytes were received, then an error is returned. If false, then this function will expect to read exactly one byte, 0xFF, and will return an error otherwise. |
Definition at line 476 of file RoboClaw.cpp.
References _calcCRC(), _parameters, _uart, _uart_set, _uart_timeout, read(), TIMEOUT_US, and write().
Referenced by _sendNothing(), _sendSigned16Bit(), _sendUnsigned7Bit(), readEncoder(), and taskMain().
int RoboClaw::drive | ( | float | value | ) |
Drive both motors.
+1 = full forward, -1 = full backward
Definition at line 406 of file RoboClaw.cpp.
References _sendUnsigned7Bit(), CMD_DRIVE_FWD_MIX, CMD_DRIVE_REV_MIX, and command.
Referenced by taskMain().
float RoboClaw::getMotorPosition | ( | e_motor | motor | ) |
Definition at line 331 of file RoboClaw.cpp.
References _encoderCounts, MOTOR_1, MOTOR_2, and warnx.
Referenced by printStatus().
float RoboClaw::getMotorSpeed | ( | e_motor | motor | ) |
Definition at line 345 of file RoboClaw.cpp.
References _motorSpeeds, MOTOR_1, MOTOR_2, and warnx.
Referenced by printStatus().
void RoboClaw::printStatus | ( | char * | string, |
size_t | n | ||
) |
print status
Definition at line 322 of file RoboClaw.cpp.
References getMotorPosition(), getMotorSpeed(), MOTOR_1, and MOTOR_2.
int RoboClaw::readEncoder | ( | ) |
read data from serial
Definition at line 255 of file RoboClaw.cpp.
References _encoderCounts, _lastEncoderCount, _motorSpeeds, _transaction(), CMD_READ_BOTH_ENCODERS, CMD_READ_SPEED_1, CMD_READ_SPEED_2, ENCODER_MESSAGE_SIZE, ENCODER_SPEED_MESSAGE_SIZE, and TIMEOUT_RETRIES.
Referenced by taskMain().
int RoboClaw::resetEncoders | ( | ) |
reset the encoders
Definition at line 418 of file RoboClaw.cpp.
References _sendNothing(), and CMD_RESET_ENCODERS.
Referenced by RoboClaw().
int RoboClaw::setMotorDutyCycle | ( | e_motor | motor, |
float | value | ||
) |
set the duty cycle of a motor
Definition at line 387 of file RoboClaw.cpp.
References _sendSigned16Bit(), CMD_SIGNED_DUTYCYCLE_1, CMD_SIGNED_DUTYCYCLE_2, command, MOTOR_1, and MOTOR_2.
Referenced by ~RoboClaw().
int RoboClaw::setMotorSpeed | ( | e_motor | motor, |
float | value | ||
) |
set the speed of a motor, rev/sec
Definition at line 359 of file RoboClaw.cpp.
References _sendUnsigned7Bit(), CMD_DRIVE_FWD_1, CMD_DRIVE_FWD_2, CMD_DRIVE_REV_1, CMD_DRIVE_REV_2, command, MOTOR_1, and MOTOR_2.
void RoboClaw::taskMain | ( | ) |
Definition at line 135 of file RoboClaw.cpp.
References _actuatorArmed, _actuatorControls, _actuatorsSub, _armedSub, _encoderCounts, _motorSpeeds, _parameters, _parameters_update(), _paramSub, _paramUpdate, _transaction(), _wheelEncoderMsg, _wheelEncodersAdv, actuator_armed_s::armed, CMD_READ_STATUS, actuator_controls_s::control, disarmed, drive(), actuator_armed_s::force_failsafe, hrt_absolute_time(), ll40ls::instance, actuator_armed_s::lockdown, actuator_armed_s::manual_lockdown, orb_advertise_multi(), orb_copy(), ORB_ID, ORB_PRIO_DEFAULT, orb_publish(), orb_set_interval(), orb_subscribe(), orb_unsubscribe(), readEncoder(), STOP_RETRIES, taskShouldExit, TIMEOUT_US, and turn().
Referenced by roboclaw_thread_main().
int RoboClaw::turn | ( | float | value | ) |
Turn.
+1 = full right, -1 = full left
Definition at line 412 of file RoboClaw.cpp.
References _sendUnsigned7Bit(), CMD_TURN_LEFT, CMD_TURN_RIGHT, and command.
Referenced by taskMain().
|
private |
Definition at line 202 of file RoboClaw.hpp.
Referenced by taskMain().
|
private |
Definition at line 199 of file RoboClaw.hpp.
Referenced by taskMain().
|
private |
actuator controls subscription
Definition at line 198 of file RoboClaw.hpp.
Referenced by _parameters_update(), RoboClaw(), and taskMain().
|
private |
Definition at line 201 of file RoboClaw.hpp.
Referenced by taskMain().
|
private |
Definition at line 211 of file RoboClaw.hpp.
Referenced by getMotorPosition(), readEncoder(), RoboClaw(), and taskMain().
|
private |
Definition at line 210 of file RoboClaw.hpp.
Referenced by readEncoder(), and RoboClaw().
|
private |
Definition at line 212 of file RoboClaw.hpp.
Referenced by getMotorSpeed(), readEncoder(), RoboClaw(), and taskMain().
struct { ... } RoboClaw::_param_handles |
Referenced by _parameters_update(), and RoboClaw().
struct { ... } RoboClaw::_parameters |
Referenced by _parameters_update(), _transaction(), RoboClaw(), and taskMain().
|
private |
Definition at line 204 of file RoboClaw.hpp.
Referenced by taskMain().
|
private |
Definition at line 205 of file RoboClaw.hpp.
Referenced by taskMain().
|
private |
Definition at line 193 of file RoboClaw.hpp.
Referenced by _transaction(), RoboClaw(), and ~RoboClaw().
|
private |
Definition at line 194 of file RoboClaw.hpp.
Referenced by _transaction(), and RoboClaw().
|
private |
Definition at line 195 of file RoboClaw.hpp.
Referenced by _transaction().
|
private |
Definition at line 208 of file RoboClaw.hpp.
Referenced by taskMain().
|
private |
Definition at line 207 of file RoboClaw.hpp.
Referenced by taskMain().
int32_t RoboClaw::actuator_write_period_ms |
Definition at line 181 of file RoboClaw.hpp.
param_t RoboClaw::actuator_write_period_ms |
Definition at line 189 of file RoboClaw.hpp.
int32_t RoboClaw::address |
Definition at line 182 of file RoboClaw.hpp.
param_t RoboClaw::address |
Definition at line 190 of file RoboClaw.hpp.
int32_t RoboClaw::counts_per_rev |
Definition at line 179 of file RoboClaw.hpp.
param_t RoboClaw::counts_per_rev |
Definition at line 187 of file RoboClaw.hpp.
int32_t RoboClaw::encoder_read_period_ms |
Definition at line 180 of file RoboClaw.hpp.
param_t RoboClaw::encoder_read_period_ms |
Definition at line 188 of file RoboClaw.hpp.
speed_t RoboClaw::serial_baud_rate |
Definition at line 178 of file RoboClaw.hpp.
param_t RoboClaw::serial_baud_rate |
Definition at line 186 of file RoboClaw.hpp.
|
static |
Definition at line 67 of file RoboClaw.hpp.
Referenced by roboclaw_main(), and taskMain().