Skip to content

Initial velocity can be specified in config#677

Open
heuristicus wants to merge 3 commits into
rai-opensource:mainfrom
ori-goals:max-vel-defaults
Open

Initial velocity can be specified in config#677
heuristicus wants to merge 3 commits into
rai-opensource:mainfrom
ori-goals:max-vel-defaults

Conversation

@heuristicus
Copy link
Copy Markdown
Contributor

@heuristicus heuristicus commented Jun 9, 2025

Change Overview

Allows the default starting velocity of the robot to be specified from the configuration or parameters. This is convenient when operating with specific restrictions so that they can be put in place in the configuration rather than having to be manually specified by the user each time the driver boots.

Testing Done

Started the robot with velocity values of 0.5 and confirmed that it moves slower.

@heuristicus heuristicus marked this pull request as ready for review June 9, 2025 16:22
self.declare_parameter("use_velodyne", False)
self.declare_parameter("velodyne_rate", 10.0)


Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@heuristicus nit: redundant blank line.

velocity.velocity_limit.linear.x = self.get_parameter("max_linear_x").value
velocity.velocity_limit.linear.y = self.get_parameter("max_linear_y").value
velocity.velocity_limit.angular.z = self.get_parameter("max_angular_z").value
self.handle_max_vel(velocity, SetVelocity.Response())
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@heuristicus may I suggest we split out the necessary functionality from SpotROS2.handle_max_vel rather than faking a service call?


self.declare_parameter("max_linear_x", 1.0)
self.declare_parameter("max_linear_y", 1.0)
self.declare_parameter("max_angular_z", 1.0)
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@heuristicus hmm, I'm inclined to suggest that if no velocity caps are specified, no velocity caps should be enforced. 1 m/s, 1 rad/s limits seem reasonable but arbitrary.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants