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 }
 
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  Registers {
  REG_STOP_START = 0x00, REG_BRAKE_STOP = 0x01, REG_CRUISE_STOP = 0x02, REG_LEFT_PWM = 0x03,
  REG_RIGHT_PWM = 0x04, REG_LEFT_SPEED_SET = 0x07, REG_RIGHT_SPEED_SET = 0x08, REG_LEFT_RAMP = 0x09,
  REG_RIGHT_RAMP = 0x0A, REG_LEFT_ODOM = 0x0B, REG_RIGHT_ODOM = 0x0C, REG_DEADMAN = 0x0D,
  REG_LEFT_CURRENT = 0x0E, REG_RIGHT_CURRENT = 0x0F, REG_ERROR_COUNT = 0x10, REG_5V_MAIN_ERROR = 0x11,
  REG_5V_AUX_ERROR = 0x12, REG_12V_MAIN_ERROR = 0x13, REG_12V_AUX_ERROR = 0x14, REG_5V_MAIN_OL = 0x15,
  REG_5V_AUX_OL = 0x16, REG_12V_MAIN_OL = 0x17, REG_12V_AUX_OL = 0x18, REG_UNUSED_19 = 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_12V_MAIN_CURRENT = 0x25,
  REG_5V_AUX_CURRENT = 0x26, REG_12V_AUX_CURRENT = 0x27, REG_LEFT_SPEED_MEASURED = 0x28, REG_RIGHT_SPEED_MEASURED = 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, 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
}
 

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

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

Static Private Member Functions

static uint8_t generateChecksum (const std::vector< uint8_t > &data)
 
static uint8_t generateChecksum (const RawMotorMessage &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

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

Detailed Description

Definition at line 55 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 189 of file motor_message.h.

◆ HwOptions

Enumerator
OPT_ENC_6_STATE 

Definition at line 158 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 163 of file motor_message.h.

◆ MessageTypes

Enumerator
TYPE_READ 
TYPE_WRITE 
TYPE_RESPONSE 
TYPE_ERROR 

Definition at line 62 of file motor_message.h.

◆ Registers

Enumerator
REG_STOP_START 
REG_BRAKE_STOP 
REG_CRUISE_STOP 
REG_LEFT_PWM 
REG_RIGHT_PWM 
REG_LEFT_SPEED_SET 
REG_RIGHT_SPEED_SET 
REG_LEFT_RAMP 
REG_RIGHT_RAMP 
REG_LEFT_ODOM 
REG_RIGHT_ODOM 
REG_DEADMAN 
REG_LEFT_CURRENT 
REG_RIGHT_CURRENT 
REG_ERROR_COUNT 
REG_5V_MAIN_ERROR 
REG_5V_AUX_ERROR 
REG_12V_MAIN_ERROR 
REG_12V_AUX_ERROR 
REG_5V_MAIN_OL 
REG_5V_AUX_OL 
REG_12V_MAIN_OL 
REG_12V_AUX_OL 
REG_UNUSED_19 
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_12V_MAIN_CURRENT 
REG_5V_AUX_CURRENT 
REG_12V_AUX_CURRENT 
REG_LEFT_SPEED_MEASURED 
REG_RIGHT_SPEED_MEASURED 
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 
DEBUG_50 
DEBUG_51 
DEBUG_52 
DEBUG_53 
DEBUG_54 
DEBUG_55 
DEBUG_56 
DEBUG_57 
DEBUG_58 

Definition at line 70 of file motor_message.h.

Constructor & Destructor Documentation

◆ MotorMessage()

MotorMessage::MotorMessage ( )
inline

Definition at line 58 of file motor_message.h.

◆ ~MotorMessage()

MotorMessage::~MotorMessage ( )
inline

Definition at line 59 of file motor_message.h.

Member Function Documentation

◆ deserialize()

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

Definition at line 148 of file motor_message.cc.

◆ generateChecksum() [1/2]

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

◆ generateChecksum() [2/2]

uint8_t MotorMessage::generateChecksum ( const RawMotorMessage data)
staticprivate

Definition at line 197 of file motor_message.cc.

◆ getData()

int32_t MotorMessage::getData ( ) const

Definition at line 132 of file motor_message.cc.

◆ getRegister()

MotorMessage::Registers MotorMessage::getRegister ( ) const

Definition at line 119 of file motor_message.cc.

◆ getType()

MotorMessage::MessageTypes MotorMessage::getType ( ) const

Definition at line 109 of file motor_message.cc.

◆ serialize()

RawMotorMessage MotorMessage::serialize ( ) const

Definition at line 138 of file motor_message.cc.

◆ setData()

void MotorMessage::setData ( int32_t  data)

Definition at line 123 of file motor_message.cc.

◆ setRegister()

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

Definition at line 113 of file motor_message.cc.

◆ setType()

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

Definition at line 103 of file motor_message.cc.

◆ verifyRegister()

int MotorMessage::verifyRegister ( uint8_t  r)
staticprivate

Definition at line 187 of file motor_message.cc.

◆ verifyType()

int MotorMessage::verifyType ( uint8_t  t)
staticprivate

Definition at line 178 of file motor_message.cc.

Member Data Documentation

◆ data

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

Definition at line 209 of file motor_message.h.

◆ delimeter

const uint8_t MotorMessage::delimeter = 0x7E
static

Definition at line 200 of file motor_message.h.

◆ MOT_POW_ACTIVE

const int32_t MotorMessage::MOT_POW_ACTIVE = 0x0001
static

Definition at line 174 of file motor_message.h.

◆ protocol_version

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

Definition at line 211 of file motor_message.h.

◆ register_addr

uint8_t MotorMessage::register_addr
private

Definition at line 206 of file motor_message.h.

◆ type

uint8_t MotorMessage::type
private

Definition at line 204 of file motor_message.h.

◆ valid_registers

uint8_t const MotorMessage::valid_registers
staticprivate

Definition at line 215 of file motor_message.h.

◆ valid_types

uint8_t const 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 214 of file motor_message.h.


The documentation for this class was generated from the following files:


ubiquity_motor
Author(s):
autogenerated on Mon Feb 28 2022 23:57:06