Skip to content

Commit

Permalink
Allow params to take on namespaces as prefixes (#1)
Browse files Browse the repository at this point in the history
  • Loading branch information
tbalch-tri authored and GitHub Enterprise committed Nov 11, 2021
1 parent 0b55637 commit 193362a
Showing 1 changed file with 15 additions and 15 deletions.
30 changes: 15 additions & 15 deletions ackermann_cmd_mux/src/throttle_interpolator.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,29 +11,29 @@ class InterpolateThrottle:
def __init__(self):

# Allow our topics to be dynamic.
self.rpm_input_topic = rospy.get_param('~rpm_input_topic', '/vesc/commands/motor/unsmoothed_speed')
self.rpm_output_topic = rospy.get_param('~rpm_output_topic', '/vesc/commands/motor/speed')
self.rpm_input_topic = rospy.get_param('~rpm_input_topic', 'commands/motor/unsmoothed_speed')
self.rpm_output_topic = rospy.get_param('~rpm_output_topic', 'commands/motor/speed')

self.servo_input_topic = rospy.get_param('~servo_input_topic', '/vesc/commands/servo/unsmoothed_position')
self.servo_output_topic = rospy.get_param('~servo_output_topic', '/vesc/commands/servo/position')
self.servo_input_topic = rospy.get_param('~servo_input_topic', 'commands/servo/unsmoothed_position')
self.servo_output_topic = rospy.get_param('~servo_output_topic', 'commands/servo/position')

self.max_acceleration = rospy.get_param('/vesc/max_acceleration')
self.max_rpm = rospy.get_param('/vesc/vesc_driver/speed_max')
self.min_rpm = rospy.get_param('/vesc/vesc_driver/speed_min')
self.throttle_smoother_rate = rospy.get_param('/vesc/throttle_smoother_rate')
self.speed_to_erpm_gain = rospy.get_param('/vesc/speed_to_erpm_gain')
self.max_acceleration = rospy.get_param('max_acceleration')
self.max_rpm = rospy.get_param('vesc_driver/speed_max')
self.min_rpm = rospy.get_param('vesc_driver/speed_min')
self.throttle_smoother_rate = rospy.get_param('throttle_smoother_rate')
self.speed_to_erpm_gain = rospy.get_param('speed_to_erpm_gain')

self.max_servo_speed = rospy.get_param('/vesc/max_servo_speed')
self.steering_angle_to_servo_gain = rospy.get_param('/vesc/steering_angle_to_servo_gain')
self.servo_smoother_rate = rospy.get_param('/vesc/servo_smoother_rate')
self.max_servo = rospy.get_param('/vesc/vesc_driver/servo_max')
self.min_servo = rospy.get_param('/vesc/vesc_driver/servo_min')
self.max_servo_speed = rospy.get_param('max_servo_speed')
self.steering_angle_to_servo_gain = rospy.get_param('steering_angle_to_servo_gain')
self.servo_smoother_rate = rospy.get_param('servo_smoother_rate')
self.max_servo = rospy.get_param('vesc_driver/servo_max')
self.min_servo = rospy.get_param('vesc_driver/servo_min')

# Variables
self.last_rpm = 0
self.desired_rpm = self.last_rpm

self.last_servo = rospy.get_param('/vesc/steering_angle_to_servo_offset')
self.last_servo = rospy.get_param('steering_angle_to_servo_offset')
self.desired_servo_position = self.last_servo

# Create topic subscribers and publishers
Expand Down

0 comments on commit 193362a

Please sign in to comment.