webots
webots copied to clipboard
SolidReference and/or JointParameters block the movement of a LinearMotor
Describe the Bug In a certain configuration, using at the same time SolidReference and JointParameters block the movement of a LinearMotor.
Steps to Reproduce
- Open the following world :
world file
#VRML_SIM R2021a utf8
WorldInfo {
coordinateSystem "NUE"
}
Viewpoint {
orientation -0.9351235864913506 -0.31827338836034974 -0.1557110408711453 0.9640363489590187
position -1.87889558080866 7.2834176780814746 6.396411931107234
}
TexturedBackground {
}
TexturedBackgroundLight {
}
Robot {
children [
Solid {
translation 2 0 0
children [
Shape {
geometry Cylinder {
}
}
]
}
Solid {
children [
Shape {
geometry Box {
}
}
SliderJoint {
jointParameters JointParameters {
}
device [
LinearMotor {
}
]
endPoint SolidReference {
solidName "solid"
}
}
]
name "solid(1)"
}
]
controller "my_controller"
}
- Create a controller named my_controller and use the following code :
controller file
#include <webots/robot.h> #include <webots/motor.h>#define TIME_STEP 64 int main(int argc, char **argv) { wb_robot_init(); WbDeviceTag motor = wb_robot_get_device("linear motor"); while (wb_robot_step(TIME_STEP) != -1) { wb_motor_set_position(motor, 2); }; wb_robot_cleanup(); return 0; }
- Run simulation. nothing move. Thank to the the linear motor, the cylinder should translate away from the cube. See that the "position" field in "jointParameters" change to 2 (which is the requested position in the controller), but without the cylinder actually moving.
- Remove the joinParameters. Run again, everything work fine (cylinder move)
- Add back the joinParameters, and replace the SolidReference by the actual Solid (which is named "solid", and hold the cylinder)
- Run simulation again, cylinder move fine.
- Of course, doing both (removing joinParameters and replacing SolidReference) make it work
Expected behavior The same movement should be produced whatever the case.
System
- Operating System: Debian 11
- Webots from master c3c2f47
I'm inspecting the problem because there is clearly a bug given that it should behave the same with and without JointParameters set.
However, the mechanical loop in the given world is wrong.
It is impossible that the SliderJoint.endPoint can move given that it references a Solid statically attached to the Robot instance that cannot move.