Public Types | Public Member Functions | Static Public Attributes | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
MotorMessage Class Reference

#include <motor_message.h>

Public Types

enum  ErrorCodes {
  ERR_NONE = 0, ERR_DELIMITER = 1, ERR_WRONG_PROTOCOL = 2, ERR_BAD_CHECKSUM = 3,
  ERR_BAD_TYPE = 4, ERR_UNKNOWN_REGISTER = 5
}
 
enum  HwOptions {
  OPT_ENC_6_STATE = 0x01, OPT_WHEEL_TYPE_THIN = 0x02, OPT_WHEEL_DIR_REVERSE = 0x04, OPT_DRIVE_TYPE_4WD = 0x08,
  OPT_WHEEL_TYPE_STANDARD = 0, OPT_DRIVE_TYPE_STANDARD = 0, OPT_WHEEL_DIR_STANDARD = 0
}
 
enum  Limits {
  LIM_M1_PWM = 0x10, LIM_M2_PWM = 0x01, LIM_M1_INTEGRAL = 0x20, LIM_M2_INTEGRAL = 0x02,
  LIM_M1_MAX_SPD = 0x40, LIM_M2_MAX_SPD = 0x4, LIM_PARAM_LIMIT = 0x80
}
 
enum  MessageTypes { TYPE_READ = 0xA, TYPE_WRITE = 0xB, TYPE_RESPONSE = 0xC, TYPE_ERROR = 0xD }
 
enum  PidControlActions {
  PID_CTRL_NO_SPECIAL_MODES = 0x000, PID_CTRL_RESET = 0x001, PID_CTRL_PWM_OVERRIDE = 0x002, PID_CTRL_P_ONLY_ON_0_VEL = 0x004,
  PID_CTRL_USE_ONLY_P_TERM = 0x008, PID_CTRL_SQUARED_ERROR = 0x010, PID_CTRL_CAP_POS_SETPOINT = 0x020, PID_CTRL_BOOST_P_TERM = 0x040,
  PID_CTRL_BOOST_P_TURBO = 0x080, PID_CTRL_AUTOSHIFT_TO_SQUARED = 0x100, PID_CTRL_AUTOSHIFT_TO_BOOST_P = 0x200, PID_CTRL_USE_VELOCITY_TERM = 0x800
}
 
enum  Registers {
  REG_STOP_START = 0x00, REG_BRAKE_STOP = 0x01, REG_SYSTEM_EVENTS = 0x02, REG_LEFT_PWM = 0x03,
  REG_RIGHT_PWM = 0x04, REG_PWM_BOTH_WHLS = 0x07, REG_TINT_BOTH_WHLS = 0x08, REG_09 = 0x09,
  REG_DRIVE_TYPE = 0x0A, REG_RIGHT_RAMP = 0x0A, REG_WHEEL_NULL_ERR = 0x0b, REG_WHEEL_DIR = 0x0C,
  REG_DEADMAN = 0x0D, REG_LEFT_CURRENT = 0x0E, REG_RIGHT_CURRENT = 0x0F, REG_WHEEL_TYPE = 0x10,
  REG_PID_ERROR_CAP = 0x11, REG_OPTION_SWITCH = 0x12, REG_PWM_OVERRIDE = 0x13, REG_PID_CONTROL = 0x14,
  REG_PARAM_V_RDY = 0x15, REG_PARAM_P_RDY = 0x16, REG_PARAM_I_RDY = 0x17, REG_PARAM_D_RDY = 0x18,
  REG_PARAM_C_RDY = 0x19, REG_PARAM_V = 0x1A, REG_PARAM_P = 0x1B, REG_PARAM_I = 0x1C,
  REG_PARAM_D = 0x1D, REG_PARAM_C = 0x1E, REG_LED_1 = 0x1F, REG_LED_2 = 0x20,
  REG_HARDWARE_VERSION = 0x21, REG_FIRMWARE_VERSION = 0x22, REG_BATTERY_VOLTAGE = 0x23, REG_5V_MAIN_CURRENT = 0x24,
  REG_MAINV_TPOINT = 0x25, REG_12V_MAIN_CURRENT = 0x26, REG_AUXV_TPOINT = 0x27, REG_BATT_VOL_LOW = 0x28,
  REG_VBUF_SIZ = 0x29, REG_BOTH_SPEED_SET = 0x2A, REG_MOVING_BUF_SIZE = 0x2B, REG_LIMIT_REACHED = 0x2C,
  REG_BOTH_ERROR = 0x2D, REG_BOTH_ODOM = 0x30, REG_ROBOT_ID = 0x31, REG_MOT_PWR_ACTIVE = 0x32,
  REG_ESTOP_ENABLE = 0x33, REG_PID_MAX_ERROR = 0x34, REG_MAX_SPEED_FWD = 0x35, REG_MAX_SPEED_REV = 0x36,
  REG_MAX_PWM = 0x37, REG_HW_OPTIONS = 0x38, REG_DEADZONE = 0x39, REG_FIRMWARE_DATE = 0x3a,
  REG_STEST_REQUEST = 0x3b, REG_STEST_RESULTS = 0x3c, DEBUG_50 = 0x50, DEBUG_51 = 0x51,
  DEBUG_52 = 0x52, DEBUG_53 = 0x53, DEBUG_54 = 0x54, DEBUG_55 = 0x55,
  DEBUG_56 = 0x56, DEBUG_57 = 0x57, DEBUG_58 = 0x58
}
 
enum  StestRequestAndResults {
  STEST_IDLE = 0x00000000, STEST_MAINV = 0x00000001, STEST_AUXV = 0x00000002, STEST_BATTERY = 0x00000004,
  STEST_BATTERY_LOW = 0x00000008, STEST_MOT_PWR = 0x00000080, STEST_MOTOR_AND_ENCS = 0x00000100, STEST_MOTOR_POWER_ON = 0x00000400,
  STEST_M1_CURNT = 0x00001000, STEST_M2_CURNT = 0x00002000, STEST_MOT_M1_ENC = 0x00010000, STEST_MOT_M2_ENC = 0x00020000,
  STEST_IN_PROGRESS = 0x00800000, STEST_STATE = (0xF << STEST_STATE_SHIFT)
}
 
enum  SystemEvents { SYS_EVENT_POWERON = 0x00000001 }
 

Public Member Functions

MotorMessage::ErrorCodes deserialize (const RawMotorMessage &serialized)
 
int32_t getData () const
 
MotorMessage::Registers getRegister () const
 
MotorMessage::MessageTypes getType () const
 
 MotorMessage ()
 
RawMotorMessage serialize () const
 
void setData (int32_t data)
 
void setRegister (MotorMessage::Registers reg)
 
void setType (MotorMessage::MessageTypes type)
 
 ~MotorMessage ()
 

Static Public Attributes

const static uint8_t delimeter = 0x7E
 
const static int32_t MOT_POW_ACTIVE = 0x0001
 

Static Private Member Functions

static uint8_t generateChecksum (const RawMotorMessage &data)
 
static uint8_t generateChecksum (const std::vector< uint8_t > &data)
 
static int verifyRegister (uint8_t r)
 
static int verifyType (uint8_t t)
 

Private Attributes

boost::array< uint8_t, 4 > data
 
uint8_t register_addr
 
uint8_t type
 

Static Private Attributes

const static uint8_t protocol_version
 
const static uint8_t valid_registers []
 
const static uint8_t valid_types []
 

Detailed Description

Definition at line 67 of file motor_message.h.

Member Enumeration Documentation

◆ ErrorCodes

Enumerator
ERR_NONE 
ERR_DELIMITER 
ERR_WRONG_PROTOCOL 
ERR_BAD_CHECKSUM 
ERR_BAD_TYPE 
ERR_UNKNOWN_REGISTER 

Definition at line 256 of file motor_message.h.

◆ HwOptions

Enumerator
OPT_ENC_6_STATE 
OPT_WHEEL_TYPE_THIN 
OPT_WHEEL_DIR_REVERSE 
OPT_DRIVE_TYPE_4WD 
OPT_WHEEL_TYPE_STANDARD 
OPT_DRIVE_TYPE_STANDARD 
OPT_WHEEL_DIR_STANDARD 

Definition at line 192 of file motor_message.h.

◆ Limits

Enumerator
LIM_M1_PWM 
LIM_M2_PWM 
LIM_M1_INTEGRAL 
LIM_M2_INTEGRAL 
LIM_M1_MAX_SPD 
LIM_M2_MAX_SPD 
LIM_PARAM_LIMIT 

Definition at line 230 of file motor_message.h.

◆ MessageTypes

Enumerator
TYPE_READ 
TYPE_WRITE 
TYPE_RESPONSE 
TYPE_ERROR 

Definition at line 74 of file motor_message.h.

◆ PidControlActions

Enumerator
PID_CTRL_NO_SPECIAL_MODES 
PID_CTRL_RESET 
PID_CTRL_PWM_OVERRIDE 
PID_CTRL_P_ONLY_ON_0_VEL 
PID_CTRL_USE_ONLY_P_TERM 
PID_CTRL_SQUARED_ERROR 
PID_CTRL_CAP_POS_SETPOINT 
PID_CTRL_BOOST_P_TERM 
PID_CTRL_BOOST_P_TURBO 
PID_CTRL_AUTOSHIFT_TO_SQUARED 
PID_CTRL_AUTOSHIFT_TO_BOOST_P 
PID_CTRL_USE_VELOCITY_TERM 

Definition at line 176 of file motor_message.h.

◆ Registers

Enumerator
REG_STOP_START 
REG_BRAKE_STOP 
REG_SYSTEM_EVENTS 
REG_LEFT_PWM 
REG_RIGHT_PWM 
REG_PWM_BOTH_WHLS 
REG_TINT_BOTH_WHLS 
REG_09 
REG_DRIVE_TYPE 
REG_RIGHT_RAMP 
REG_WHEEL_NULL_ERR 
REG_WHEEL_DIR 
REG_DEADMAN 
REG_LEFT_CURRENT 
REG_RIGHT_CURRENT 
REG_WHEEL_TYPE 
REG_PID_ERROR_CAP 
REG_OPTION_SWITCH 
REG_PWM_OVERRIDE 
REG_PID_CONTROL 
REG_PARAM_V_RDY 
REG_PARAM_P_RDY 
REG_PARAM_I_RDY 
REG_PARAM_D_RDY 
REG_PARAM_C_RDY 
REG_PARAM_V 
REG_PARAM_P 
REG_PARAM_I 
REG_PARAM_D 
REG_PARAM_C 
REG_LED_1 
REG_LED_2 
REG_HARDWARE_VERSION 
REG_FIRMWARE_VERSION 
REG_BATTERY_VOLTAGE 
REG_5V_MAIN_CURRENT 
REG_MAINV_TPOINT 
REG_12V_MAIN_CURRENT 
REG_AUXV_TPOINT 
REG_BATT_VOL_LOW 
REG_VBUF_SIZ 
REG_BOTH_SPEED_SET 
REG_MOVING_BUF_SIZE 
REG_LIMIT_REACHED 
REG_BOTH_ERROR 
REG_BOTH_ODOM 
REG_ROBOT_ID 
REG_MOT_PWR_ACTIVE 
REG_ESTOP_ENABLE 
REG_PID_MAX_ERROR 
REG_MAX_SPEED_FWD 
REG_MAX_SPEED_REV 
REG_MAX_PWM 
REG_HW_OPTIONS 
REG_DEADZONE 
REG_FIRMWARE_DATE 
REG_STEST_REQUEST 
REG_STEST_RESULTS 
DEBUG_50 
DEBUG_51 
DEBUG_52 
DEBUG_53 
DEBUG_54 
DEBUG_55 
DEBUG_56 
DEBUG_57 
DEBUG_58 

Definition at line 82 of file motor_message.h.

◆ StestRequestAndResults

Enumerator
STEST_IDLE 
STEST_MAINV 
STEST_AUXV 
STEST_BATTERY 
STEST_BATTERY_LOW 
STEST_MOT_PWR 
STEST_MOTOR_AND_ENCS 
STEST_MOTOR_POWER_ON 
STEST_M1_CURNT 
STEST_M2_CURNT 
STEST_MOT_M1_ENC 
STEST_MOT_M2_ENC 
STEST_IN_PROGRESS 
STEST_STATE 

Definition at line 206 of file motor_message.h.

◆ SystemEvents

Enumerator
SYS_EVENT_POWERON 

Definition at line 225 of file motor_message.h.

Constructor & Destructor Documentation

◆ MotorMessage()

MotorMessage::MotorMessage ( )
inline

Definition at line 70 of file motor_message.h.

◆ ~MotorMessage()

MotorMessage::~MotorMessage ( )
inline

Definition at line 71 of file motor_message.h.

Member Function Documentation

◆ deserialize()

MotorMessage::ErrorCodes MotorMessage::deserialize ( const RawMotorMessage serialized)

Definition at line 151 of file motor_message.cc.

◆ generateChecksum() [1/2]

uint8_t MotorMessage::generateChecksum ( const RawMotorMessage data)
staticprivate

Definition at line 200 of file motor_message.cc.

◆ generateChecksum() [2/2]

static uint8_t MotorMessage::generateChecksum ( const std::vector< uint8_t > &  data)
staticprivate

◆ getData()

int32_t MotorMessage::getData ( ) const

Definition at line 135 of file motor_message.cc.

◆ getRegister()

MotorMessage::Registers MotorMessage::getRegister ( ) const

Definition at line 122 of file motor_message.cc.

◆ getType()

MotorMessage::MessageTypes MotorMessage::getType ( ) const

Definition at line 112 of file motor_message.cc.

◆ serialize()

RawMotorMessage MotorMessage::serialize ( ) const

Definition at line 141 of file motor_message.cc.

◆ setData()

void MotorMessage::setData ( int32_t  data)

Definition at line 126 of file motor_message.cc.

◆ setRegister()

void MotorMessage::setRegister ( MotorMessage::Registers  reg)

Definition at line 116 of file motor_message.cc.

◆ setType()

void MotorMessage::setType ( MotorMessage::MessageTypes  type)

Definition at line 106 of file motor_message.cc.

◆ verifyRegister()

int MotorMessage::verifyRegister ( uint8_t  r)
staticprivate

Definition at line 190 of file motor_message.cc.

◆ verifyType()

int MotorMessage::verifyType ( uint8_t  t)
staticprivate

Definition at line 181 of file motor_message.cc.

Member Data Documentation

◆ data

boost::array<uint8_t, 4> MotorMessage::data
private

Definition at line 276 of file motor_message.h.

◆ delimeter

const static uint8_t MotorMessage::delimeter = 0x7E
static

Definition at line 267 of file motor_message.h.

◆ MOT_POW_ACTIVE

const static int32_t MotorMessage::MOT_POW_ACTIVE = 0x0001
static

Definition at line 241 of file motor_message.h.

◆ protocol_version

const static uint8_t MotorMessage::protocol_version
staticprivate
Initial value:
=
0x03

Definition at line 278 of file motor_message.h.

◆ register_addr

uint8_t MotorMessage::register_addr
private

Definition at line 273 of file motor_message.h.

◆ type

uint8_t MotorMessage::type
private

Definition at line 271 of file motor_message.h.

◆ valid_registers

const uint8_t MotorMessage::valid_registers
staticprivate

Definition at line 282 of file motor_message.h.

◆ valid_types

const uint8_t MotorMessage::valid_types
staticprivate
Initial value:

Copyright (c) 2016, Ubiquity Robotics All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.

Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

Neither the name of ubiquity_motor nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Definition at line 281 of file motor_message.h.


The documentation for this class was generated from the following files:
MotorMessage::TYPE_RESPONSE
@ TYPE_RESPONSE
Definition: motor_message.h:77
MotorMessage::TYPE_ERROR
@ TYPE_ERROR
Definition: motor_message.h:78
MotorMessage::TYPE_READ
@ TYPE_READ
Definition: motor_message.h:75
MotorMessage::TYPE_WRITE
@ TYPE_WRITE
Definition: motor_message.h:76


ubiquity_motor
Author(s):
autogenerated on Thu Nov 16 2023 03:30:56