#include <motor_hardware.h>
Classes | |
struct | Joint |
Public Member Functions | |
MotorHardware (ros::NodeHandle nh) | |
void | readInputs () |
void | requestOdometry () |
void | requestVelocity () |
void | requestVersion () |
void | sendPid () |
void | setPid (int32_t p, int32_t i, int32_t d, int32_t denominator) |
void | writeSpeeds () |
~MotorHardware () | |
Private Attributes | |
int32_t | d_value |
int32_t | denominator_value |
int32_t | i_value |
hardware_interface::JointStateInterface | joint_state_interface_ |
struct MotorHardware::Joint | joints_ [2] |
MotorSerial * | motor_serial_ |
int32_t | p_value |
hardware_interface::VelocityJointInterface | velocity_joint_interface_ |
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 42 of file motor_hardware.h.
Definition at line 45 of file motor_hardware.cc.
Definition at line 88 of file motor_hardware.cc.
void MotorHardware::readInputs | ( | ) |
Definition at line 92 of file motor_hardware.cc.
void MotorHardware::requestOdometry | ( | ) |
Definition at line 189 of file motor_hardware.cc.
void MotorHardware::requestVelocity | ( | ) |
Definition at line 208 of file motor_hardware.cc.
void MotorHardware::requestVersion | ( | ) |
Definition at line 180 of file motor_hardware.cc.
void MotorHardware::sendPid | ( | ) |
Definition at line 234 of file motor_hardware.cc.
void MotorHardware::setPid | ( | int32_t | p, |
int32_t | i, | ||
int32_t | d, | ||
int32_t | denominator | ||
) |
Definition at line 227 of file motor_hardware.cc.
void MotorHardware::writeSpeeds | ( | ) |
Definition at line 124 of file motor_hardware.cc.
int32_t MotorHardware::d_value [private] |
Definition at line 59 of file motor_hardware.h.
int32_t MotorHardware::denominator_value [private] |
Definition at line 60 of file motor_hardware.h.
int32_t MotorHardware::i_value [private] |
Definition at line 58 of file motor_hardware.h.
Definition at line 54 of file motor_hardware.h.
struct MotorHardware::Joint
MotorHardware::joints_[2] [private] |
MotorSerial* MotorHardware::motor_serial_ [private] |
Definition at line 73 of file motor_hardware.h.
int32_t MotorHardware::p_value [private] |
Definition at line 57 of file motor_hardware.h.
Definition at line 55 of file motor_hardware.h.