#include <motor_hardware.h>
Classes | |
struct | Joint |
Public Member Functions | |
MotorHardware (ros::NodeHandle nh, CommsParams serial_params, FirmwareParams firmware_params) | |
void | readInputs () |
void | requestVersion () |
void | sendParams () |
void | setDeadmanTimer (int32_t deadman) |
void | setDebugLeds (bool led1, bool led2) |
void | setParams (FirmwareParams firmware_params) |
void | writeSpeeds () |
virtual | ~MotorHardware () |
Public Member Functions inherited from hardware_interface::RobotHW | |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
RobotHW () | |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual | ~RobotHW () |
Public Member Functions inherited from hardware_interface::InterfaceManager | |
T * | get () |
std::vector< std::string > | getInterfaceResources (std::string iface_type) const |
std::vector< std::string > | getNames () const |
void | registerInterface (T *iface) |
void | registerInterfaceManager (InterfaceManager *iface_man) |
Public Attributes | |
int | firmware_version |
Private Member Functions | |
void | _addOdometryRequest (std::vector< MotorMessage > &commands) const |
void | _addVelocityRequest (std::vector< MotorMessage > &commands) const |
double | calculateRadiansFromTics (int16_t tics) const |
int16_t | calculateTicsFromRadians (double radians) const |
FRIEND_TEST (MotorHardwareTests, nonZeroWriteSpeedsOutputs) | |
FRIEND_TEST (MotorHardwareTests, odomUpdatesPosition) | |
FRIEND_TEST (MotorHardwareTests, odomUpdatesPositionMax) | |
Additional Inherited Members | |
Protected Types inherited from hardware_interface::InterfaceManager | |
typedef std::vector< InterfaceManager * > | InterfaceManagerVector |
typedef std::map< std::string, void * > | InterfaceMap |
typedef std::map< std::string, std::vector< std::string > > | ResourceMap |
typedef std::map< std::string, size_t > | SizeMap |
Protected Attributes inherited from hardware_interface::InterfaceManager | |
boost::ptr_vector< ResourceManagerBase > | interface_destruction_list_ |
InterfaceManagerVector | interface_managers_ |
InterfaceMap | interfaces_ |
InterfaceMap | interfaces_combo_ |
SizeMap | num_ifaces_registered_ |
ResourceMap | resources_ |
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 48 of file motor_hardware.h.
MotorHardware::MotorHardware | ( | ros::NodeHandle | nh, |
CommsParams | serial_params, | ||
FirmwareParams | firmware_params | ||
) |
Definition at line 47 of file motor_hardware.cc.
|
virtual |
Definition at line 107 of file motor_hardware.cc.
|
private |
|
private |
|
private |
Definition at line 365 of file motor_hardware.cc.
|
private |
Definition at line 360 of file motor_hardware.cc.
|
private |
|
private |
|
private |
void MotorHardware::readInputs | ( | ) |
Definition at line 109 of file motor_hardware.cc.
void MotorHardware::requestVersion | ( | ) |
Definition at line 239 of file motor_hardware.cc.
void MotorHardware::sendParams | ( | ) |
Definition at line 264 of file motor_hardware.cc.
void MotorHardware::setDeadmanTimer | ( | int32_t | deadman | ) |
Definition at line 247 of file motor_hardware.cc.
void MotorHardware::setDebugLeds | ( | bool | led1, |
bool | led2 | ||
) |
Definition at line 334 of file motor_hardware.cc.
void MotorHardware::setParams | ( | FirmwareParams | firmware_params | ) |
Definition at line 256 of file motor_hardware.cc.
void MotorHardware::writeSpeeds | ( | ) |
Definition at line 217 of file motor_hardware.cc.
|
private |
Definition at line 76 of file motor_hardware.h.
int MotorHardware::firmware_version |
Definition at line 61 of file motor_hardware.h.
|
private |
Definition at line 70 of file motor_hardware.h.
|
private |
|
private |
Definition at line 89 of file motor_hardware.h.
|
private |
Definition at line 113 of file motor_hardware.h.
|
private |
Definition at line 73 of file motor_hardware.h.
|
private |
Definition at line 74 of file motor_hardware.h.
|
private |
Definition at line 93 of file motor_hardware.h.
|
private |
Definition at line 95 of file motor_hardware.h.
|
private |
Definition at line 97 of file motor_hardware.h.
|
private |
Definition at line 99 of file motor_hardware.h.
|
private |
Definition at line 101 of file motor_hardware.h.
|
private |
Definition at line 103 of file motor_hardware.h.
|
private |
Definition at line 105 of file motor_hardware.h.
|
private |
Definition at line 107 of file motor_hardware.h.
|
private |
Definition at line 109 of file motor_hardware.h.
|
private |
Definition at line 111 of file motor_hardware.h.
|
private |
Definition at line 92 of file motor_hardware.h.
|
private |
Definition at line 94 of file motor_hardware.h.
|
private |
Definition at line 96 of file motor_hardware.h.
|
private |
Definition at line 98 of file motor_hardware.h.
|
private |
Definition at line 100 of file motor_hardware.h.
|
private |
Definition at line 102 of file motor_hardware.h.
|
private |
Definition at line 104 of file motor_hardware.h.
|
private |
Definition at line 106 of file motor_hardware.h.
|
private |
Definition at line 108 of file motor_hardware.h.
|
private |
Definition at line 110 of file motor_hardware.h.
|
private |
Definition at line 90 of file motor_hardware.h.
|
private |
Definition at line 78 of file motor_hardware.h.
|
private |
Definition at line 71 of file motor_hardware.h.