#include <ubiquity_motor/motor_hardware.h>
#include <ubiquity_motor/motor_message.h>
#include <boost/assign.hpp>
#include <boost/math/special_functions/round.hpp>
#include <linux/i2c-dev.h>
#include <linux/i2c.h>
#include <fcntl.h>
#include <sys/ioctl.h>
Go to the source code of this file.
Macros | |
#define | HIGH_SPEED_RADIANS (1.8) |
#define | I2C_DEVICE "/dev/i2c-1" |
#define | LOWEST_FIRMWARE_VERSION 28 |
#define | MOTOR_AMPS_PER_ADC_COUNT ((double)(0.0238)) |
#define | ODOM_4WD_ROTATION_SCALE ((double)(1.65)) |
#define | TICKS_PER_RAD_FROM_GEAR_RATIO ((double)(4.774556)*(double)(2.0)) |
#define | TICKS_PER_RADIAN_DEFAULT 41.004 |
#define | VELOCITY_READ_PER_SECOND ((double)(10.0)) |
#define | WHEEL_GEAR_RATIO_DEFAULT WHEEL_GEAR_RATIO_1 |
#define | WHEEL_VELOCITY_NEAR_ZERO ((double)(0.08)) |
Functions | |
static int | i2c_BufferRead (const char *i2cDevFile, uint8_t i2c8bitAddr, uint8_t *pBuffer, int16_t chipRegAddr, uint16_t NumBytesToRead) |
Variables | |
double | g_odom4wdRotationScale = ODOM_4WD_ROTATION_SCALE |
int32_t | g_odomEvent = 0 |
int32_t | g_odomLeft = 0 |
int32_t | g_odomRight = 0 |
double | g_radiansLeft = 0.0 |
double | g_radiansRight = 0.0 |
const static uint8_t | I2C_PCF8574_8BIT_ADDR = 0x40 |
const static float | LI_ION [11] |
const static float | SLA_AGM [11] |
#define HIGH_SPEED_RADIANS (1.8) |
Definition at line 57 of file motor_hardware.cc.
#define I2C_DEVICE "/dev/i2c-1" |
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 40 of file motor_hardware.cc.
#define LOWEST_FIRMWARE_VERSION 28 |
Definition at line 64 of file motor_hardware.cc.
#define MOTOR_AMPS_PER_ADC_COUNT ((double)(0.0238)) |
Definition at line 61 of file motor_hardware.cc.
#define ODOM_4WD_ROTATION_SCALE ((double)(1.65)) |
Definition at line 59 of file motor_hardware.cc.
#define TICKS_PER_RAD_FROM_GEAR_RATIO ((double)(4.774556)*(double)(2.0)) |
Definition at line 52 of file motor_hardware.cc.
#define TICKS_PER_RADIAN_DEFAULT 41.004 |
Definition at line 53 of file motor_hardware.cc.
#define VELOCITY_READ_PER_SECOND ((double)(10.0)) |
Definition at line 63 of file motor_hardware.cc.
#define WHEEL_GEAR_RATIO_DEFAULT WHEEL_GEAR_RATIO_1 |
Definition at line 54 of file motor_hardware.cc.
#define WHEEL_VELOCITY_NEAR_ZERO ((double)(0.08)) |
Definition at line 58 of file motor_hardware.cc.
|
static |
Definition at line 1287 of file motor_hardware.cc.
double g_odom4wdRotationScale = ODOM_4WD_ROTATION_SCALE |
Definition at line 105 of file motor_hardware.cc.
int32_t g_odomEvent = 0 |
Definition at line 69 of file motor_hardware.cc.
int32_t g_odomLeft = 0 |
Definition at line 67 of file motor_hardware.cc.
int32_t g_odomRight = 0 |
Definition at line 68 of file motor_hardware.cc.
double g_radiansLeft = 0.0 |
Definition at line 108 of file motor_hardware.cc.
double g_radiansRight = 0.0 |
Definition at line 109 of file motor_hardware.cc.
|
static |
Definition at line 41 of file motor_hardware.cc.
|
static |
Definition at line 88 of file motor_hardware.cc.
|
static |
Definition at line 72 of file motor_hardware.cc.