Comments (3)
Interesting, thank you for working out the cause of this. I think your addition to the handle trajectory function is sensible and likely the best solution. I don't recall exactly when I added the velocity limits, but there have been several updates to the SDK since then so it's possible that something has changed about how it works in terms of velocity limits. Since the default seems to no longer function, it would be a good idea to also change the defaults to some relatively low values rather than zero.
Your check may also need to look at the angular velocity, since I assume if that is set to zero that the robot cannot rotate, which will limit its movement as well.
from spot_ros.
A possible cause can be that you have the autonomy_enabled
param set to false, but this would show up as an error message if the command was forbidden as a result of that.
I think you are likely sending an incorrect goal - it should be TrajectoryGoal
and not TrajectoryActionGoal
.
A useful thing to know would be whether you have the same issue if you use the code from the 1.0.0 tag, but try this after checking the other stuff. I tested the new wrapper implementation and didn't notice any issues with trajectory navigation.
from spot_ros.
You're correct, I changed TrajectoryActionGoal
to TrajectoryGoal
, and the code stopped returning an error, but the robot still didn't move after the command was sent.
I checked autonomy_enabled
, which was set to True, and then tried using the code under the 1.0.0 tag, and the problem still persisted.
I then checked the driver launch file, and noticed the lines which set the maximum x and y linear speed, with the comment stating that leaving these speeds at 0 applies spot's internal limits.
On a whim, I changed these arguments to 1.5 and 1.5, and now the robot responds to trajectory commands!
I'm not sure if my robot's speed limits are set internally on some control panel or something, but its working now.
To fix this, such that a warning is added, I tried adding this to the robot_allowed_to_move
function, on line 643 of spot_ros:
velocity_ok=True
mobility_params = self.spot_wrapper.get_mobility_params()
max_lin_vel_x=mobility_params.vel_limit.max_vel.linear.x
max_lin_vel_y=mobility_params.vel_limit.max_vel.linear.y
if max_lin_vel_x==0 or max_lin_vel_y==0:
rospy.logwarn("Spot will not move as its linear x or y velocity is set to 0. ")
velocity_ok=False
return self.allow_motion and autonomy_ok and velocity_ok
This works fine, and gives a warning, but it has the unintended side effect of stopping standing if the x and y velocity limits are set to 0, which isn't desired.
Instead I've added the following to the handle_trajectory
function:
mobility_params = self.spot_wrapper.get_mobility_params()
max_lin_vel_x=mobility_params.vel_limit.max_vel.linear.x
max_lin_vel_y=mobility_params.vel_limit.max_vel.linear.y
if max_lin_vel_x==0 or max_lin_vel_y==0:
rospy.logerr(
"Spot will not move as its linear x or y velocity is set to 0. "
)
self.trajectory_server.set_aborted(
TrajectoryResult(False, "Velocity limits set to 0.")
)
return
This seems like a good solution to me: let me know if you think there's a better way of handling it. If not, I'll commit these changes and push them to the repo
from spot_ros.
Related Issues (20)
- Announcement: Coordination with ros2 version
- Depth clouds are not published unless there is a subscriber on the image topic for that camera
- Error when starting the driver on ROS Melodic on Ubuntu 18.04.5 LTS on a SpotCORE HOT 5
- Blender File HOT 3
- Is the spot_driver is compatible with any 3D map creator? HOT 1
- Package installation after v1.0.0
- Rviz buttons are enabled if the robot is powered on but someone else has the lease
- Improve comments in code and messages
- OpenSSL Handshake failed HOT 3
- Spot rotating when trajectory pose commands are not in body reference frame HOT 4
- Is anyone else encountering issues with gmapping? HOT 1
- Several nodes not loading on driver launch HOT 7
- joint states frame rate HOT 1
- TF_REPEATED_DATA ignoring data with redundant timestamp HOT 4
- Spot Arm URDF appears to be faulty HOT 3
- Unable to get data from payload camera HOT 6
- 'catkin build' or 'catkin_make' HOT 4
- Duplicated publish_depth_images_callback method HOT 1
- Unable to publish the camera extrinsic parameters HOT 1
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from spot_ros.