Versions Compared

Key

  • This line was added.
  • This line was removed.
  • Formatting was changed.

...

  • Polaris GEM Series (e2/e4/e6/eLXD)
  • Polaris Ranger X900
  • International Prostar+ 122
  • More coming soon...

Published Topics

Message TypeTopic Name

Description

can_msgs/Framecan_rxAll data published on this topic is intended to be sent to the PACMod system via a CAN interface.
pacmod_msgs/GlobalRptparsed_tx/global_rptHigh-level data about the entire PACMod system.
pacmod_msgs/SystemRptFloatparsed_tx/accel_rptStatus and parsed values [pct] of the throttle subsystem.
pacmod_msgs/SystemRptFloatparsed_tx/brake_rptStatus and parsed values [pct] of the steering susbsystem.
pacmod_msgs/SystemRptIntparsed_tx/turn_rptStatus and parsed values [enum] of the turn signal subsystem.
pacmod_msgs/SystemRptIntparsed_tx/shift_rptStatus and parsed values [enum] of the gear/transmission subsystem.
pacmod_msgs/SystemRptFloatparsed_tx/steer_rptStatus and parsed values [rad] of the steering susbsystem.
pacmod_msgs/VehicleSpeedRptparsed_tx/vehicle_speed_rpt

The vehicle's current speed [mph], the validity of the speed message [bool], and the raw CAN message from the vehicle CAN.

std_msgs/Float64as_tx/vehicle_speedThe vehicle's current speed [m/s].
std_msgs/Boolas_tx/enableThe current status of the PACMod's control of the vehicle. If the PACMod is enabled, this value will be true. If it is disabled or overridden, this value will be false.

Conditionally Published Topics (Dependent Upon Vehicle Type)

SystemRptIntbrake brake brake brake brake brake
Message TypeTopic NameDescription
pacmod_msgs/parsed_tx/wiper_rptStatus and parsed values [enum] of the windshield wiper subsystem.
pacmod_msgs/SystemRptIntparsed_tx/headlight_rptStatus and parsed values [enum] of the headlight subsystem.
pacmod_msgs/SystemRptIntparsed_tx/horn_rptStatus and parsed values [enum] of the horn subsystem.
pacmod_msgs/SystemRptFloatparsed_tx/steer_rpt_2TBD
pacmod_msgs/SystemRptFloatparsed_tx/steer_rpt_3TBD
pacmod_msgs/MotorRpt1parsed_tx/steerbrake_rpt_detail_1Motor detail report values for the steering brake motor (current [A] and position [rad]).
pacmod_msgs/MotorRpt2parsed_tx/steerbrake_rpt_detail_2Motor detail report values for the steering brake motor (encoder temp [C], motor temp [C], and rotation velocity [rad/s]).
pacmod_msgs/MotorRpt3parsed_tx/steerbrake_rpt_detail_3Motor detail report values for the steering brake motor (torque output and input [Nm]).
pacmod_msgs/SystemRptIntparsed_tx/headlight_rptStatus and parsed values [enum] of the headlight subsystem.
pacmod_msgs/SystemRptIntparsed_tx/horn_rptStatus and parsed values [enum] of the horn subsystem.
pacmod_msgs/MotorRpt1parsed_tx/steer_rpt_detail_1Motor detail report values for the steering motor (current [A] and position [rad]).
pacmod_msgs/MotorRpt2parsed_tx/steer_rpt_detail_2Motor detail report values for the steering motor (encoder temp [C], motor temp [C], and rotation velocity [rad/s]).
pacmod_msgs/MotorRpt3parsed_tx/steer_rpt_detail_3Motor detail report values for the steering motor (torque output and input [Nm]).
pacmod_msgs/WheelSpeedRptLatLonHeadingRptparsed_tx/lat_lon_heading_rptThe current latitude, longitude, and heading provided by the vehicle's internal GPS.
pacmod_msgs/ParkingBrakeStatusRptparsed_tx/wheelparking_brake_speedstatus_rptSpeeds of individual wheels [m/s]Status on the current state of the parking brake (engaged/disengaged).
pacmod_msgs/SteeringPIDRpt1parsed_tx/steer_pid_rpt_1Current dt, Kp, Ki, and Kd values of the torque-based steering control PID loop.
pacmod_msgs/SteeringPIDRpt2parsed_tx/steer_pid_rpt_2Current P, I, and D terms and the sum of P, I, and D terms of the torque-based steering control PID loop.
pacmod_msgs/SteeringPIDRpt3parsed_tx/steer_pid_rpt_3The new torque, torque feedback, calculated angular position, and error values from the torque-based steering control PID loop.
pacmod_msgs/YawRateRptWheelSpeedRptparsed_tx/yawwheel_ratespeed_rptThe yaw rate reported by the vehicle's internal IMUSpeeds of individual wheels [m/s].
pacmod_msgs/LatLonHeadingRptSystemRptIntparsed_tx/latwiper_lon_heading_rptThe current latitude, longitude, and heading provided by the vehicle's internal GPSStatus and parsed values [enum] of the windshield wiper subsystem.
pacmod_msgs/ParkingBrakeStatusRptYawRateRptparsed_tx/parkingyaw_brakerate_status_rptStatus on the current state of the parking brake (engaged/disengaged)The yaw rate reported by the vehicle's internal IMU.

Subscribed Topics

Message TypeTopic NameDescription
can_msgs/Framecan_txAll data published to this topic will be parsed by the PACMod driver. This should be connected to a CAN interface.
pacmod_msgs/PacmodCmdas_rx/turn_cmdCommands the turn signal subsystem to transition to a given state [enum].
pacmod_msgs/PacmodCmdas_rx/shift_cmdCommands the gear/transmission subsystem to shift to a different gear [enum].
pacmod_msgs/PacmodCmdas_rx/accel_cmdCommands the throttle subsystem to seek a specific pedal position [pct - 0.0 to 1.0].
pacmod_msgs/PositionWithSpeedas_rx/steer_cmdCommands the steering subsystem to seek a specific steering wheel angle [rad] at a given rotation velocity [rad/s].
pacmod_msgs/PacmodCmdas_rx/brake_cmdCommands the brake subsystem to seek a specific pedal position [pct - 0.0 to 1.0].
std_msgs/Boolas_rx/enableEnables [true] or disables [false] PACMod's control of the vehicle.

...