Initial velocity can be specified in config#677
Open
heuristicus wants to merge 3 commits into
Open
Conversation
| self.declare_parameter("use_velodyne", False) | ||
| self.declare_parameter("velodyne_rate", 10.0) | ||
|
|
||
|
|
| 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()) |
Collaborator
There was a problem hiding this comment.
@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) |
Collaborator
There was a problem hiding this comment.
@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.
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
Add this suggestion to a batch that can be applied as a single commit.This suggestion is invalid because no changes were made to the code.Suggestions cannot be applied while the pull request is closed.Suggestions cannot be applied while viewing a subset of changes.Only one suggestion per line can be applied in a batch.Add this suggestion to a batch that can be applied as a single commit.Applying suggestions on deleted lines is not supported.You must change the existing code in this line in order to create a valid suggestion.Outdated suggestions cannot be applied.This suggestion has been applied or marked resolved.Suggestions cannot be applied from pending reviews.Suggestions cannot be applied on multi-line comments.Suggestions cannot be applied while the pull request is queued to merge.Suggestion cannot be applied right now. Please check back later.
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.