Classes | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
MotorHardware Class Reference

#include <motor_hardware.h>

Inheritance diagram for MotorHardware:
Inheritance graph
[legend]

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)
 

Private Attributes

int32_t deadman_timer
 
hardware_interface::JointStateInterface joint_state_interface_
 
struct MotorHardware::Joint joints_ [2]
 
ros::Publisher leftError
 
MotorSerialmotor_serial_
 
FirmwareParams pid_params
 
FirmwareParams prev_pid_params
 
ros::Publisher pubS50
 
ros::Publisher pubS51
 
ros::Publisher pubS52
 
ros::Publisher pubS53
 
ros::Publisher pubS54
 
ros::Publisher pubS55
 
ros::Publisher pubS56
 
ros::Publisher pubS57
 
ros::Publisher pubS58
 
ros::Publisher pubS59
 
ros::Publisher pubU50
 
ros::Publisher pubU51
 
ros::Publisher pubU52
 
ros::Publisher pubU53
 
ros::Publisher pubU54
 
ros::Publisher pubU55
 
ros::Publisher pubU56
 
ros::Publisher pubU57
 
ros::Publisher pubU58
 
ros::Publisher pubU59
 
ros::Publisher rightError
 
int32_t sendPid_count
 
hardware_interface::VelocityJointInterface velocity_joint_interface_
 

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< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

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 48 of file motor_hardware.h.

Constructor & Destructor Documentation

MotorHardware::MotorHardware ( ros::NodeHandle  nh,
CommsParams  serial_params,
FirmwareParams  firmware_params 
)

Definition at line 47 of file motor_hardware.cc.

MotorHardware::~MotorHardware ( )
virtual

Definition at line 107 of file motor_hardware.cc.

Member Function Documentation

void MotorHardware::_addOdometryRequest ( std::vector< MotorMessage > &  commands) const
private
void MotorHardware::_addVelocityRequest ( std::vector< MotorMessage > &  commands) const
private
double MotorHardware::calculateRadiansFromTics ( int16_t  tics) const
private

Definition at line 365 of file motor_hardware.cc.

int16_t MotorHardware::calculateTicsFromRadians ( double  radians) const
private

Definition at line 360 of file motor_hardware.cc.

MotorHardware::FRIEND_TEST ( MotorHardwareTests  ,
nonZeroWriteSpeedsOutputs   
)
private
MotorHardware::FRIEND_TEST ( MotorHardwareTests  ,
odomUpdatesPosition   
)
private
MotorHardware::FRIEND_TEST ( MotorHardwareTests  ,
odomUpdatesPositionMax   
)
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.

Member Data Documentation

int32_t MotorHardware::deadman_timer
private

Definition at line 76 of file motor_hardware.h.

int MotorHardware::firmware_version

Definition at line 61 of file motor_hardware.h.

hardware_interface::JointStateInterface MotorHardware::joint_state_interface_
private

Definition at line 70 of file motor_hardware.h.

struct MotorHardware::Joint MotorHardware::joints_[2]
private
ros::Publisher MotorHardware::leftError
private

Definition at line 89 of file motor_hardware.h.

MotorSerial* MotorHardware::motor_serial_
private

Definition at line 113 of file motor_hardware.h.

FirmwareParams MotorHardware::pid_params
private

Definition at line 73 of file motor_hardware.h.

FirmwareParams MotorHardware::prev_pid_params
private

Definition at line 74 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS50
private

Definition at line 93 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS51
private

Definition at line 95 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS52
private

Definition at line 97 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS53
private

Definition at line 99 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS54
private

Definition at line 101 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS55
private

Definition at line 103 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS56
private

Definition at line 105 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS57
private

Definition at line 107 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS58
private

Definition at line 109 of file motor_hardware.h.

ros::Publisher MotorHardware::pubS59
private

Definition at line 111 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU50
private

Definition at line 92 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU51
private

Definition at line 94 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU52
private

Definition at line 96 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU53
private

Definition at line 98 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU54
private

Definition at line 100 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU55
private

Definition at line 102 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU56
private

Definition at line 104 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU57
private

Definition at line 106 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU58
private

Definition at line 108 of file motor_hardware.h.

ros::Publisher MotorHardware::pubU59
private

Definition at line 110 of file motor_hardware.h.

ros::Publisher MotorHardware::rightError
private

Definition at line 90 of file motor_hardware.h.

int32_t MotorHardware::sendPid_count
private

Definition at line 78 of file motor_hardware.h.

hardware_interface::VelocityJointInterface MotorHardware::velocity_joint_interface_
private

Definition at line 71 of file motor_hardware.h.


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


ubiquity_motor
Author(s):
autogenerated on Mon Jun 10 2019 15:37:24