Public Types | Public Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes
MotorMessage Class Reference

#include <motor_message.h>

List of all members.

Public Types

enum  MessageTypes { TYPE_READ = 0xAA, TYPE_WRITE = 0xBB, TYPE_RESPONSE = 0xCC }
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_LEFT_MOTOR_ERROR = 0x19,
  REG_RIGHT_MOTOR_ERROR = 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
}

Public Member Functions

int deserialize (const std::vector< uint8_t > &serialized)
int32_t getData () const
MotorMessage::Registers getRegister () const
MotorMessage::MessageTypes getType () const
 MotorMessage ()
std::vector< uint8_t > serialize () const
void setData (int32_t data)
void setRegister (MotorMessage::Registers reg)
void setType (MotorMessage::MessageTypes type)
 ~MotorMessage ()

Static Private Member Functions

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

Private Attributes

uint8_t data [4]
uint8_t register_addr
uint8_t type

Static Private Attributes

static const uint8_t delimeter = 0x7E
static const uint8_t protocol_version = 0x02
static const uint8_t valid_registers []
static const uint8_t valid_types []

Detailed Description

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 37 of file motor_message.h.


Member Enumeration Documentation

Enumerator:
TYPE_READ 
TYPE_WRITE 
TYPE_RESPONSE 

Definition at line 45 of file motor_message.h.

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_LEFT_MOTOR_ERROR 
REG_RIGHT_MOTOR_ERROR 
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 

Definition at line 52 of file motor_message.h.


Constructor & Destructor Documentation

Definition at line 41 of file motor_message.h.

Definition at line 42 of file motor_message.h.


Member Function Documentation

int MotorMessage::deserialize ( const std::vector< uint8_t > &  serialized)

Definition at line 140 of file motor_message.cc.

uint8_t MotorMessage::generateChecksum ( const std::vector< uint8_t > &  data) [static, private]

Definition at line 199 of file motor_message.cc.

int32_t MotorMessage::getData ( ) const

Definition at line 118 of file motor_message.cc.

Definition at line 102 of file motor_message.cc.

Definition at line 90 of file motor_message.cc.

std::vector< uint8_t > MotorMessage::serialize ( ) const

Definition at line 126 of file motor_message.cc.

void MotorMessage::setData ( int32_t  data)

Definition at line 110 of file motor_message.cc.

Definition at line 96 of file motor_message.cc.

Definition at line 84 of file motor_message.cc.

int MotorMessage::verifyRegister ( uint8_t  r) [static, private]

Definition at line 188 of file motor_message.cc.

int MotorMessage::verifyType ( uint8_t  t) [static, private]

Definition at line 177 of file motor_message.cc.


Member Data Documentation

uint8_t MotorMessage::data[4] [private]

Definition at line 125 of file motor_message.h.

const uint8_t MotorMessage::delimeter = 0x7E [static, private]

Definition at line 127 of file motor_message.h.

const uint8_t MotorMessage::protocol_version = 0x02 [static, private]

Definition at line 128 of file motor_message.h.

uint8_t MotorMessage::register_addr [private]

Definition at line 124 of file motor_message.h.

uint8_t MotorMessage::type [private]

Definition at line 123 of file motor_message.h.

uint8_t const MotorMessage::valid_registers [static, private]

Definition at line 131 of file motor_message.h.

uint8_t const MotorMessage::valid_types [static, private]
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 130 of file motor_message.h.


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


ubiquity_motor
Author(s):
autogenerated on Thu Jun 6 2019 18:33:28