Skip to end of metadata
Go to start of metadata

You are viewing an old version of this page. View the current version.

Compare with Current View Page History

« Previous Version 17 Current »

driver_name: pacmod
msgs_name: pacmod_msgs

An open-source ROS driver for interacting with the PACMod (v1 and v2 only) drive-by-wire system.

Supported Hardware

  • Polaris GEM Series (e2/e4/e6/eLXD)
  • Polaris Ranger X900
  • International Prostar+ 122
  • Lexus RX-450h
  • 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)

Message TypeTopic NameDescription
pacmod_msgs/MotorRpt1parsed_tx/brake_rpt_detail_1Motor detail report values for the brake motor (current [A] and position [rad]).
pacmod_msgs/MotorRpt2parsed_tx/brake_rpt_detail_2Motor detail report values for the brake motor (encoder temp [C], motor temp [C], and rotation velocity [rad/s]).
pacmod_msgs/MotorRpt3parsed_tx/brake_rpt_detail_3Motor detail report values for the 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/LatLonHeadingRptparsed_tx/lat_lon_heading_rptThe current latitude, longitude, and heading provided by the vehicle's internal GPS.
pacmod_msgs/ParkingBrakeStatusRptparsed_tx/parking_brake_status_rptStatus 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/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/WheelSpeedRptparsed_tx/wheel_speed_rptSpeeds of individual wheels [m/s].
pacmod_msgs/SystemRptIntparsed_tx/wiper_rptStatus and parsed values [enum] of the windshield wiper subsystem.
pacmod_msgs/YawRateRptparsed_tx/yaw_rate_rptThe 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/accel_cmdCommands the throttle subsystem to seek a specific pedal position [pct - 0.0 to 1.0].
pacmod_msgs/PacmodCmdas_rx/brake_cmdCommands the brake subsystem to seek a specific pedal position [pct - 0.0 to 1.0].
pacmod_msgs/PacmodCmdas_rx/shift_cmdCommands the gear/transmission subsystem to shift to a different gear [enum].
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/turn_cmdCommands the turn signal subsystem to transition to a given state [enum].
std_msgs/Boolas_rx/enableEnables [true] or disables [false] PACMod's control of the vehicle.

Parameters


~vehicle_type
    A string value indicating the type of vehicle to which the PACMod is connected. Valid values are: POLARIS_GEM, POLARIS_RANGER, INTERNATIONAL_PROSTAR_122, and LEXUS_RX_450H.

  • No labels