uuv_simulator
uuv_simulator copied to clipboard
Can't launch custom actuated thruster actuated vehicle model after using wiki
Hello,
I am trying to use this package, and I was following your wiki page on creating a new vehicle and launching it with UUV_Simulator here: https://github.com/uuvsimulator/uuv_simulator/wiki/Templates-to-create-a-new-thruster-actuated-vehicle-model
I'm currently having issues with trying to launch my vehicle. I'm getting this error:
uuv_simulator/uuv_gazebo_plugins/uuv_gazebo_plugins/src/ThrusterPlugin.cc:81: virtual void gazebo::ThrusterPlugin::Load(gazebo::physics::ModelPtr, sdf::ElementPtr): Assertion `(_sdf->HasElement("thrusterID"))&&("Thruster ID was not provided")' failed. Aborted (core dumped) [gazebo-2] process has died [pid 7725, exit code 134, cmd /opt/ros/kinetic/lib/gazebo_ros/gzserver --verbose -e ode worlds/ocean_waves.world __name:=gazebo __log:=/home/andrew/.ros/log/1430a016-67f0-11e7-ad4f-64006a646a5f/gazebo-2.log]. log file: /home/andrew/.ros/log/1430a016-67f0-11e7-ad4f-64006a646a5f/gazebo-2*.log
My generated urdf looks as such: test.urdf.txt
Hey, thanks for pointing this out!
You are right. It looks like there is a line missing in the tutorial snippets:
Within the <plugin>
block of the thruster plugin, there should be a line:
<thrusterID>${thruster_id}</thrusterID>
We will fix it in the tutorials. In the meantime, could you check whether it works after adding this line?
If in doubt you can also have a look at the code of our rexrov model. But please let us know if you find more issues
Best, Sebastian
@sebastianscherer So I added the line in, and it launches. My model instantly sinks though. Based off of the volume and mass of the vehicle, it /should/ float. It does float in real life. Any idea what I'm getting that?
Also. When I launch it, I keep getting this warning message:
[Wrn] [UnderwaterObjectPlugin.cc:207] Relative angular acceleration is invalid -nan
And idea what's causing that?
I should state that I found the lines:
else if (std::isnan(linearAccel))
{
gzwarn << "Relative linear acceleration is invalid" << std::endl
<< linearAccel << std::endl;
}
else if (std::isnan(angularAccel))
{
gzwarn << "Relative angular acceleration is invalid" << std::endl
<< angularAccel << std::endl;
}
I have not gone trawling through all the code, but do you know what could be causing this exactly?
We have these warnings still in there since we did sometimes experience the physics library exploding.
The two cases in which we ran into such problems were:
-
Trying to use one or multiple manipulators on a vehicle in combination with a low simulation rate (<1000 Hz). Robust simulation of manipulators with Gazebo seems to require some tuning of the parameters.
-
When simulating added masses that are larger than the actual mass of the vehicle. This can lead to numerical problems because of the way we currently trick regular physics engines into simulating hydrodynamic effects (6x6 mass matrices). We successfully simulated a wide range that do not have this problem, but if this is what indeed causing you problems, we can turn the currently hard-coded value here a variable (and you should choose it much lower in this case).
I hope this helps. If you can share more information about you model we might be able to find out more.
@sebastianscherer That does actually. Considering the size of the example vehicle I'm trying to simulate...I think it's the second problem. The vehicle's mass is 6.123497kg in air, and we have a few example sensors on it. So. That may explain that.
@sebastianscherer I have another question. I tried to launch the thruster manager as per the tutorial found here: https://github.com/uuvsimulator/uuv_simulator/wiki/Setup-up-of-thruster-manager-and-simple-velocity-controller-with-joystick-teleoperation-for-a-new-vehicle
I launch it with the reset_tam:=true
argument, and it loads for a second, then it quickly crashes and gives me the following error:
could not get transform from: /videoray_pro4/base_link
to: /videoray_pro4/thruster_0
[]
Traceback (most recent call last):
File "/home/andrew/Development/aquanaut_ws/install/lib/uuv_thruster_manager/thruster_allocator.py", line 138, in <module>
node = ThrusterAllocatorNode()
File "/home/andrew/Development/aquanaut_ws/install/lib/uuv_thruster_manager/thruster_allocator.py", line 39, in __init__
ThrusterManager.__init__(self)
File "/home/andrew/Development/aquanaut_ws/install/lib/python2.7/dist-packages/uuv_thrusters/thruster_manager.py", line 133, in __init__
raise rospy.ROSException('No thrusters found')
rospy.exceptions.ROSException: No thrusters found
[videoray_pro4/thruster_allocator-1] process has died [pid 29322, exit code 1, cmd /home/andrew/Development/underwater_ws/install/lib/uuv_thruster_manager/thruster_allocator.py __name:=thruster_allocator __log:=/home/andrew/.ros/log/47faeeb4-680f-11e7-ad4f-64006a646a5f/videoray_pro4-thruster_allocator-1.log].
log file: /home/andrew/.ros/log/47faeeb4-680f-11e7-ad4f-64006a646a5f/videoray_pro4-thruster_allocator-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
done
Which is confusing to me since I have a robot state publisher call out in my launch file and since i have the joint_state_publisher
plugin called out in my xacro:
<!-- Joint state publisher plugin -->
<gazebo>
<plugin name="joint_state_publisher" filename="libjoint_state_publisher.so">
<robotNamespace>$(arg namespace)</robotNamespace>
<updateRate>50</updateRate>
</plugin>
</gazebo>
Hi, can you share your tf tree so we can check this comes from? The thruster ID fix has been merged.
@musamarcusso Attached I have my tf tree for the vehicle's robot description. frames.pdf