Go to the documentation of this file.
   31 #ifndef MOTORHARDWARE_H 
   32 #define MOTORHARDWARE_H 
   38 #include "sensor_msgs/JointState.h" 
   40 #include "std_msgs/Int32.h" 
   41 #include "std_msgs/UInt32.h" 
   42 #include "std_msgs/Float32.h" 
   43 #include "std_msgs/Bool.h" 
   44 #include "std_msgs/String.h" 
   45 #include "sensor_msgs/BatteryState.h" 
   46 #include "ubiquity_motor/MotorState.h" 
   54 #include <gtest/gtest_prod.h> 
   57 #define MIN_HW_OPTION_SWITCH 50 
  
double motorAmpsZeroAdcCount
double getWheelGearRatio(void)
float battery_voltage_low_level
bool estop_motor_power_off
void motor_pid_p_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
void battery_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
double getWheelTicksPerRadian(void)
void setSystemEvents(int32_t system_events)
void setWheelDirection(int32_t wheel_direction)
void nullWheelErrors(void)
double calculateRadiansFromTicks(int16_t ticks)
int16_t calculateSpeedFromRadians(double radians)
void setDeadmanTimer(int32_t deadman)
bool left_max_speed_limit
void setDebugLeds(bool led1, bool led2)
void setParams(FirmwareParams firmware_params)
void setPidControl(int32_t pid_control)
float battery_voltage_critical
MotorSerial * motor_serial_
void setDriveType(int32_t drive_type)
MotorHardware(ros::NodeHandle nh, NodeParams node_params, CommsParams serial_params, FirmwareParams firmware_params)
int areWheelSpeedsLower(double wheelSpeedRadPerSec)
void _addVelocityRequest(std::vector< MotorMessage > &commands) const
void publishMotorState(void)
void setHardwareVersion(int32_t hardware_version)
ros::Publisher rightCurrent
int getPidControlWord(void)
void getWheelJointPositions(double &leftWheelPosition, double &rightWheelPosition)
void setDeadzoneEnable(int32_t deadzone_enable)
ros::Publisher motor_power_active
MotorDiagnostics motor_diag_
float getBatteryVoltage(void)
void readInputs(uint32_t index)
bool right_max_speed_limit
bool estop_motor_power_off
float calculateBatteryPercentage(float voltage, int cells, const float *type)
hardware_interface::JointStateInterface joint_state_interface_
hardware_interface::VelocityJointInterface velocity_joint_interface_
void firmware_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
void requestSystemEvents()
int fw_pid_moving_buffer_size
int getOptionSwitch(void)
void setMaxRevSpeed(int32_t max_speed_rev)
void publishFirmwareInfo()
void setWheelType(int32_t wheel_type)
void setOptionSwitchReg(int32_t option_switch)
void setMaxFwdSpeed(int32_t max_speed_fwd)
void forcePidParamUpdates()
void setEstopDetection(int32_t estop_detection)
void motor_power_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
void firmware_date_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
void requestFirmwareVersion()
void requestFirmwareDate()
void setMaxPwm(int32_t max_pwm)
diagnostic_updater::Updater diag_updater
void getMotorCurrents(double ¤tLeft, double ¤tRight)
void setWheelJointVelocities(double leftWheelVelocity, double rightWheelVelocity)
ros::Publisher rightError
ros::Publisher firmware_state
void _addOdometryRequest(std::vector< MotorMessage > &commands) const
void setWheelGearRatio(double wheel_gear_ratio)
ros::Publisher leftCurrent
ros::Publisher motor_state
ros::Publisher battery_state
void motor_max_pwm_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
bool right_integral_limit
void motor_pid_d_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Publisher rightTickInterval
void motor_pid_v_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
void firmware_options_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
bool param_limit_in_firmware
FRIEND_TEST(MotorHardwareTests, nonZeroWriteSpeedsOutputs)
ros::Publisher leftTickInterval
void limit_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
diagnostic_updater::FrequencyStatus odom_update_status
void writeSpeedsInRadians(double left_radians, double right_radians)
void setEstopPidThreshold(int32_t estop_pid_threshold)
void motor_pid_i_status(diagnostic_updater::DiagnosticStatusWrapper &stat)
struct MotorHardware::Joint joints_[2]
FirmwareParams prev_fw_params