Closed hbaqueiro closed 4 years ago
Hi @hbaqueiro, could you provide the URDF of your robot model as well?
Hi @musamarcusso , sorry for the delay. I've formatted my machine and hat to follow the tutorial again. The URDF of my robot are the templates generated by rosrun uuv_assistants create_new_robot_model --robot_name baqfish
. (I named it baqfish instead of baqtronic this time). I've not edited them. I am posting the code below but they should be very much the same as if you run the command...
baqfish_description/robots/default.xacro:
<robot name="baqfish" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:arg name="debug" default="0"/>
<xacro:arg name="namespace" default="baqfish"/>
<!-- Include the ROV macro file -->
<xacro:include filename="$(find baqfish_description)/urdf/base.xacro"/>
<xacro:include filename="$(find baqfish_description)/urdf/gazebo.xacro"/>
<!-- Create the baqfish -->
<xacro:baqfish_base namespace="$(arg namespace)">
<!-- The underwater object plugin is given as an input block parameter to
allow the addition of external models of manipulator units -->
<gazebo>
<plugin name="uuv_plugin" filename="libunderwater_object_ros_plugin.so">
<fluid_density>1028.0</fluid_density>
<flow_velocity_topic>hydrodynamics/current_velocity</flow_velocity_topic>
<debug>$(arg debug)</debug>
<!-- Adding the hydrodynamic and hydrostatic parameters for the vehicle-->
<xacro:baqfish_hydro_model namespace="$(arg namespace)"/>
<!--
In case other modules are added to the vehicle (such as a manipulator)
that also have link running with the underwater object plugin, they
should also be added in this block. For this, this new module should
have a file similar to gazebo.xacro above with the description of the
parameter necessary for the underwater object plugin to be initialized.
-->
</plugin>
</gazebo>
</xacro:baqfish_base>
<!-- Joint state publisher plugin -->
<xacro:default_joint_state_publisher namespace="$(arg namespace)" update_rate="10"/>
</robot>
baqfish_description/urdf/actuators.xacro:
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Adding the thruster units with the macro created in snippets.xacro -->
<!--
Important:
- The thruster IDs must be given as integers and must be unique to each thruster unit
- The thruster pose in the <origin> block is relative to the body's center of mass. Be
aware that Gazebo does not use the SNAME convention per default.
-->
<xacro:thruster_macro robot_namespace="${namespace}" thruster_id="0">
<origin xyz="0 0 0" rpy="0 0 ${pi}" />
</xacro:thruster_macro>
<xacro:thruster_macro robot_namespace="${namespace}" thruster_id="1">
<origin xyz="0 0 0" rpy="0 0 ${pi}" />
</xacro:thruster_macro>
<xacro:thruster_macro robot_namespace="${namespace}" thruster_id="2">
<origin xyz="0 0 0" rpy="0 -${0.5*pi} 0" />
</xacro:thruster_macro>
<!-- Instantiate fins, if necessary -->
<xacro:fin_macro namespace="${namespace}" fin_id="0">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:fin_macro>
<xacro:fin_macro namespace="${namespace}" fin_id="1">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:fin_macro>
<xacro:fin_macro namespace="${namespace}" fin_id="2">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:fin_macro>
<xacro:fin_macro namespace="${namespace}" fin_id="3">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:fin_macro>
</robot>
baqfish_description/urdf/base.xacro
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Loading some constants -->
<xacro:include filename="$(find uuv_descriptions)/models/common/urdf/common.urdf.xacro"/>
<!-- Loading file with sensor macros -->
<xacro:include filename="$(find uuv_sensor_ros_plugins)/urdf/sensor_snippets.xacro"/>
<!-- Loading the UUV simulator ROS plugin macros -->
<xacro:include filename="$(find uuv_gazebo_ros_plugins)/urdf/snippets.xacro"/>
<!-- Loading vehicle's specific macros -->
<xacro:include filename="$(find baqfish_description)/urdf/snippets.xacro"/>
<!--
Vehicle's parameters (remember to enter the model parameters below)
-->
<xacro:property name="mass" value="0"/>
<!-- Center of gravity -->
<xacro:property name="cog" value="0 0 0"/>
<!-- Fluid density -->
<xacro:property name="rho" value="1028"/>
<!--
Visual mesh file for the vehicle, usually in DAE (Collada) format. Be sure to store the
mesh with the origin of the mesh on the same position of the center of mass, otherwise
the mesh pose will have to be corrected below in the <visual> block.
Open the meshes for the RexROV vehicle in Blender to see an example on the mesh placement.
-->
<xacro:property name="visual_mesh_file" value="file://$(find baqfish_description)/meshes/vehicle.dae"/>
<!-- Collision geometry mesh, usually in STL format (it is recommended to keep
this geometry as simple as possible to improve the performance the physics engine
regarding the computation of collision forces) -->
<xacro:property name="collision_mesh_file" value="file://$(find baqfish_description)/meshes/vehicle.stl"/>
<!-- Vehicle macro -->
<xacro:macro name="baqfish_base" params="namespace *gazebo">
<!-- Rigid body description of the base link -->
<link name="${namespace}/base_link">
<!--
Be careful to setup the coefficients for the inertial tensor,
otherwise your model will become unstable on Gazebo
-->
<inertial>
<mass value="${mass}" />
<origin xyz="${cog}" rpy="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0"
iyy="0" iyz="0"
izz="0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="${visual_mesh_file}" scale="1 1 1" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="${collision_mesh_file}" scale="1 1 1" />
</geometry>
</collision>
</link>
<gazebo reference="${namespace}/base_link">
<selfCollide>false</selfCollide>
</gazebo>
<!-- Set up hydrodynamic plugin given as input parameter -->
<xacro:insert_block name="gazebo"/>
<!-- Include the thruster modules -->
<xacro:include filename="$(find baqfish_description)/urdf/actuators.xacro"/>
<!-- Include the sensor modules -->
<xacro:include filename="$(find baqfish_description)/urdf/sensors.xacro"/>
</xacro:macro>
</robot>
baqfish_description/urdf/gazebo.xacro
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Center of buoyancy -->
<xacro:property name="baqfish_cob" value="0 0 0"/>
<!-- Vehicle's actual volume (Gazebo cannot compute the volume out of the mesh) -->
<xacro:property name="baqfish_volume" value="0"/>
<!-- Describing the dimensions of the vehicle's bounding box -->
<xacro:property name="baqfish_length" value="0"/>
<xacro:property name="baqfish_width" value="0"/>
<xacro:property name="baqfish_height" value="0"/>
<xacro:macro name="baqfish_hydro_model" params="namespace">
<!-- List of hydrodynamic models this robot's links -->
<link name="${namespace}/base_link">
<!-- This flag will make the link neutrally buoyant -->
<neutrally_buoyant>0</neutrally_buoyant>
<!-- Link's volume -->
<volume>${baqfish_volume}</volume>
<!-- Link's bounding box, it is used to recalculate the immersed
volume when close to the surface.
This is a workaround the invalid bounding box given by Gazebo-->
<box>
<width>${baqfish_width}</width>
<length>${baqfish_length}</length>
<height>${baqfish_height}</height>
</box>
<!-- Center of buoyancy -->
<center_of_buoyancy>${baqfish_cob}</center_of_buoyancy>
<!--
----------------------------------------------------
----------------------------------------------------
Choose one of the hydrodynamic models below, all are based on
Fossen's equation of motion for underwater vehicles
Reference:
[1] Fossen, Thor I. Handbook of marine craft hydrodynamics and motion
control. John Wiley & Sons, 2011.
----------------------------------------------------
---------------------------------------------------->
<!-- 1) Fossen's equation of motion -->
<hydrodynamic_model>
<type>fossen</type>
<added_mass>
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
</added_mass>
<!--
The linear damping coefficients can be provided as a diagonal (6 elements)
or a full matrix (36 coefficients), like the added-mass coefficients above
-->
<linear_damping>
0 0 0 0 0 0
</linear_damping>
<!--
The linear damping coefficients proportional to the forward speed
can be provided as a diagonal (6 elements) or a full matrix (36 coefficients),
like the added-mass coefficients above.
This matrix is mostly useful for slender bodies (e.g. AUVs with torpedo shape)
-->
<linear_damping_forward_speed>
0 0 0 0 0 0
</linear_damping_forward_speed>
<!--
The quadratic damping coefficients can be provided as a diagonal (6 elements)
or a full matrix (36 coefficients), like the added-mass coefficients above
-->
<quadratic_damping>
0 0 0 0 0 0
</quadratic_damping>
<!--
In case you want to model a simple surface vessel, you can use the
implementation of linear (small angle) theory for boxed shaped vessels
by providing the following parameters. If you omit the area of the
water level plane area, it will be calculated from the bounding box
parameters. Uncomment the lines below in case you are simulating a
surface vessel.
For more details on these parameters and the computation of buoyancy
for vessels using this theory, check:
[1] Lecture Notes TTK 4190 Guidance and Control of Vehicles (T. I. Fossen)
http://www.fossen.biz/wiley/Ch4.pdf
[2] Fossen, Thor I. Handbook of marine craft hydrodynamics and motion
control. John Wiley & Sons, 2011.
-->
<!--
<metacentric_width>0.0</metacentric_width>
<metacentric_length>0.0</metacentric_length>
<submerged_height>0.0</submerged_height>
-->
</hydrodynamic_model>
<!-- 2) This computes the added-mass and damping parameters for a sphere
in the fluid with the given radius -->
<hydrodynamic_model>
<type>sphere</type>
<radius>0</radius>
</hydrodynamic_model>
</link>
</xacro:macro>
</robot>
baqfish_description/urdf/sensors.xacro
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!--
Some examples of sensors that can be added to the vehicle frame.
Set the origin of the sensor frames correctly for your application
Look into the sensor macros in the package uuv_sensor_ros_plugins/urdf for
more examples or add you own custom sensor units.
-->
<!-- Mount a GPS. -->
<xacro:default_gps namespace="${namespace}" parent_link="${namespace}/base_link" />
<!-- Mount a Pose 3D sensor. -->
<xacro:default_pose_3d namespace="${namespace}" parent_link="${namespace}/base_link" />
<!-- Forward-looking sonar sensor -->
<xacro:forward_multibeam_p900 namespace="${namespace}" parent_link="${namespace}/base_link">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:forward_multibeam_p900>
<!-- DVL -->
<xacro:default_dvl namespace="${namespace}" parent_link="${namespace}/base_link">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:default_dvl>
<!-- RPT -->
<xacro:default_rpt namespace="${namespace}" parent_link="${namespace}/base_link">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:default_rpt>
<!-- Pressure -->
<xacro:default_pressure namespace="${namespace}" parent_link="${namespace}/base_link">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:default_pressure>
<!-- IMU -->
<xacro:default_imu namespace="${namespace}" parent_link="${namespace}/base_link">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:default_imu>
<!-- Mount a camera -->
<xacro:default_camera namespace="${namespace}" parent_link="${namespace}/base_link">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:default_camera>
</robot>
baqfish_description/urdf/snippets.xacro
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-------------------------------------------------------------------------->
<!-- MACRO FOR THRUSTER UNITS -->
<!-------------------------------------------------------------------------->
<!-- Provide the propeller mesh in a separate file with the rotation axis
over propeller's frame X-axis in DAE (Collada) or STL format.
-->
<xacro:property name="prop_mesh_file" value="file://$(find baqfish_description)/meshes/propeller.dae"/>
<!--
Thruster macro with integration of joint and link. The thrusters should
be initialized in the actuators.xacro file.
-->
<xacro:macro name="thruster_macro" params="robot_namespace thruster_id *origin">
<!--
Dummy link as place holder for the thruster frame,
since thrusters can often be inside the collision geometry
of the vehicle and may cause internal collisions if set otherwise
-->
<link name="${robot_namespace}/thruster_${thruster_id}">
<visual>
<geometry>
<mesh filename="${prop_mesh_file}" scale="1 1 1" />
</geometry>
</visual>
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.000000017" ixy="0.0" ixz="0.0"
iyy="0.000000017" iyz="0.0"
izz="0.000000017" />
</inertial>
</link>
<!-- Joint between thruster link and vehicle base link -->
<joint name="${robot_namespace}/thruster_${thruster_id}_joint" type="continuous">
<xacro:insert_block name="origin" />
<axis xyz="1 0 0" />
<parent link="${robot_namespace}/base_link" />
<child link="${robot_namespace}/thruster_${thruster_id}" />
</joint>
<gazebo>
<!-- Thruster ROS plugin -->
<plugin name="${robot_namespace}_${thruster_id}_thruster_model" filename="libthruster_ros_plugin.so">
<!-- Name of the thruster link -->
<linkName>${robot_namespace}/thruster_${thruster_id}</linkName>
<!-- Name of the joint between thruster and vehicle base link -->
<jointName>${robot_namespace}/thruster_${thruster_id}_joint</jointName>
<!-- Make the thruster aware of its id -->
<thrusterID>${thruster_id}</thrusterID>
<!-- Gain of the input command signal -->
<gain>1</gain>
<!-- Maximum allowed input value for the input signal for thruster unit -->
<clampMax>0</clampMax>
<!-- Minimum allowed value for the input signal for thruster unit -->
<clampMin>0</clampMin>
<!-- Minimum and maximum thrust force output allowed -->
<thrustMin>0</thrustMin>
<thrustMax>0</thrustMax>
<!--
Value from 0 to 1 to set the efficiency of the output thrust force
Default value is 1.0
-->
<thrust_efficiency>1</thrust_efficiency>
<!--
Value from 0 to 1 to set the efficiency of the propeller as a factor
to be multiplied to the current value of the state variable at each
iteration.
Default value is 1.0
-->
<propeller_efficiency>1</propeller_efficiency>
<!--
----------------------------------------------------
----------------------------------------------------
Choose one of the propeller dynamics models below for your implementation
This will describe the dynamic model for the state variable of your thruster unit,
which can be, e.g., the angular velocity of the propeller.
----------------------------------------------------
---------------------------------------------------->
<!-- 1) Simple zero-order model -->
<dynamics>
<type>ZeroOrder</type>
</dynamics>
<!-- 2) First order model -->
<dynamics>
<type>FirstOrder</type>
<timeConstant>0.0</timeConstant>
</dynamics>
<!-- 3) Yoerger's nonlinear dynamic model
For information on the model description:
[1] D. R. Yoerger, J. G. Cooke, and J.-J. E. Slotine, “The influence of
thruster dynamics on underwater vehicle behavior and their incorporation
into control system design,” IEEE Journal of Oceanic Engineering, vol. 15,
no. 3, pp. 167–178, Jul. 1990.
-->
<dynamics>
<type>Yoerger</type>
<alpha>0.0</alpha>
<beta>0.0</beta>
</dynamics>
<!-- 4) Bessa's nonlinear dynamic model
For information on the model description:
[2] Bessa, Wallace Moreira, Max Suell Dutra, and Edwin Kreuzer. "Thruster
dynamics compensation for the positioning of underwater robotic vehicles
through a fuzzy sliding mode based approach." ABCM Symposium Series in
Mechatronics. Vol. 2. 2006.
-->
<dynamics>
<type>Bessa</type>
<Jmsp>0.0</Jmsp>
<Kv1>0.0</Kv1>
<Kv2>0.0</Kv2>
<Kt>0.0</Kt>
<Rm>0.0</Rm>
</dynamics>
<!--
----------------------------------------------------
----------------------------------------------------
Choose one of the model for the steady-state curve describing the
relationship between the state variable and the output thrust force
----------------------------------------------------
---------------------------------------------------->
<!-- 1) Basic curve
Input: x
Output: thrust
Function: thrust = rotorConstant * x * abs(x)
-->
<conversion>
<type>Basic</type>
<rotorConstant>0.0</rotorConstant>
</conversion>
<!-- 2) Dead-zone nonlinearity described in Bessa, 2006
Input: x
Output: thrust
Function:
thrust = rotorConstantL * (x * abs(x) - deltaL), if x * abs(x) <= deltaL
thrust = 0, if deltaL < x * abs(x) < deltaR
thrust = rotorConstantR * (x * abs(x) - deltaR), if x * abs(x) >= deltaL
-->
<conversion>
<type>Bessa</type>
<rotorConstantL>0.0</rotorConstantL>
<rotorConstantR>0.0</rotorConstantR>
<deltaL>0.0</deltaL>
<deltaR>0.0</deltaR>
</conversion>
<!-- 3) Linear interpolation
If you have access to the thruster's data sheet, for example,
you can enter samples of the curve's input and output values
and the thruster output will be found through linear interpolation
of the given samples.
-->
<conversion>
<type>LinearInterp</type>
<inputValues>0 1 2 3</inputValues>
<outputValues>0 1 2 3</outputValues>
</conversion>
</plugin>
</gazebo>
<gazebo reference="${robot_namespace}/thruster_${thruster_id}">
<selfCollide>false</selfCollide>
</gazebo>
</xacro:macro>
<!-------------------------------------------------------------------------->
<!-- MACRO FOR FIN/RUDDER UNITS -->
<!-------------------------------------------------------------------------->
<!--
This macro can be used to add fins to the body of the vehicle, the fins
should be initialized in the actuators.xacro file. If you vehicle has no
fins, you can erase the macro below.
-->
<!-- A separate mesh for the fin should be stored in the meshes folder -->
<xacro:property name="fin_mesh_file" value="file://$(find baqfish_description)/meshes/fin.dae"/>
<!-- Fin joint limits -->
<xacro:property name="fin_min_joint_limit" value="${0.0 * d2r}"/>
<xacro:property name="fin_max_joint_limit" value="${0.0 * d2r}"/>
<xacro:macro name="fin_macro" params="namespace fin_id *origin">
<joint name="${namespace}/fin${fin_id}_joint" type="revolute">
<limit effort="0" lower="${fin_min_joint_limit}" upper="${fin_max_joint_limit}" velocity="0"/>
<xacro:insert_block name="origin"/>
<axis xyz="0 0 1"/>
<parent link="${namespace}/base_link" />
<child link="${namespace}/fin${fin_id}" />
</joint>
<link name="${namespace}/fin${fin_id}">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.000000017" ixy="0.0" ixz="0.0"
iyy="0.000000017" iyz="0.0"
izz="0.000000017" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="${fin_mesh_file}" scale="1 1 1"/>
</geometry>
</visual>
</link>
<gazebo>
<plugin name="${namespace}_fin${fin_id}_model" filename="libfin_ros_plugin.so">
<!--
----------------------------------------------------
----------------------------------------------------
First order dynamics model for the fin joint dynamics,
replace an appropriate time constant
----------------------------------------------------
----------------------------------------------------
-->
<dynamics>
<type>FirstOrder</type>
<timeConstant>0.0</timeConstant>
</dynamics>
<!--
----------------------------------------------------
----------------------------------------------------
Definition of the lift and drag model, choose ONE of the models
below according to the model you want to use.
----------------------------------------------------
----------------------------------------------------
-->
<!--
1) References for the two line lift and drag model:
[1] https://en.wikipedia.org/wiki/Lift_coefficient
[2] http://gazebosim.org/tutorials?tut=aerodynamics&cat=plugins
-->
<liftdrag>
<type>TwoLines</type>
<area>${replace here the value for the area of the fin's cross section}</area>
<fluid_density>0.0</fluid_density>
<a0>0.0</a0>
<alpha_stall>0.0</alpha_stall>
<cla>0.0</cla><!-- ^= 0.244 when using deg -->
<cla_stall>0.0</cla_stall>
<cda>0.0</cda>
<cda_stall>0.0</cda_stall>
</liftdrag>
<!--
2) Reference for the quadratic lift and drag model:
[1] Engelhardtsen, Oystein. 3D AUV Collision Avoidance.
MS thesis. Institutt for teknisk kybernetikk, 2007.
https://brage.bibsys.no/xmlui/handle/11250/259834
-->
<liftdrag>
<type>Quadratic</type>
<lift_constant>0.0</lift_constant>
<drag_constant>0.0</drag_constant>
</liftdrag>
<!--
----------------------------------------------------
----------------------------------------------------
Further parameters necessary for the lift and drag plugin
----------------------------------------------------
----------------------------------------------------
-->
<!-- Current velocity topic -->
<current_velocity_topic>/hydrodynamics/current_velocity</current_velocity_topic>
<!-- Name of the correspodent fin link and joint -->
<link_name>${namespace}/fin${fin_id}</link_name>
<joint_name>${namespace}/fin${fin_id}_joint</joint_name>
<!-- Output topic to publish the current angle of the fin joint -->
<output_topic>${namespace}/fins/${fin_id}/output</output_topic>
<input_topic>${namespace}/fins/${fin_id}/input</input_topic>
<wrench_topic>${namespace}/fins/${fin_id}/wrench_topic</wrench_topic>
</plugin>
</gazebo>
</xacro:macro>
</robot>
Hello everyone,
I'm also learning the uuv_simulator and went to the same problem. It appears to be a problem on the template's comment. Somehow it's not allowing comments like the one below:
<!--
----------------------------------------------------
----------------------------------------------------
Further parameters necessary for the lift and drag plugin
----------------------------------------------------
----------------------------------------------------
-->
Also, I realized that a suffix tag in the sensors.template was missing.
I made a pull request to fix those problems.
Dear all, I updated the autoproj to get the fixed code and created the new robot model and the thruster manager configuration again. I am still facing errors:
To check for compatibility of your document, use option --check-order.
For more infos, see http://wiki.ros.org/xacro#Processing_Order
Traceback (most recent call last):
File "/opt/ros/kinetic/share/xacro/xacro.py", line 61, in <module>
xacro.main()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/xacro/__init__.py", line 1073, in main
out.write(doc.toprettyxml(indent=' '))
UnicodeEncodeError: 'ascii' codec can't encode character u'\u201c' in position 10790: ordinal not in range(128)
Invalid <param> tag: Cannot load command parameter [robot_description]: command [/opt/ros/kinetic/share/xacro/xacro.py '/home/baqueiro/autoproj/src/baqfish_description/robots/default.xacro' debug:=0 namespace:=baqfish] returned with code [1].
Param xml is <param command="$(find xacro)/xacro.py '$(find baqfish_description)/robots/$(arg mode).xacro' debug:=$(arg debug) namespace:=$(arg namespace)" name="robot_description"/>
The traceback for the exception was written to the log file
EDIT: It turns out that there are unicode characters in the commented references preventing the vehicle to be launched. The characters are the 'LEFT DOUBLE QUOTATION MARK' (U+201C) and the EN DASH (U+2013). Replace it by the usual " and - respectively and it should work.
There are double quotation marks in: *_description/urdf/snippets.xacro uuv_simulator/uuv_assistants/templates/robot_model/urdf/snippets.xacro.template uuv_simulator/uuv_gazebo_plugins/uuv_gazebo_plugins/src/BuoyantObject.cc uuv_simulator/uuv_tutorials/uuv_tutorial_rov_model/urdf/rov_example_snippets.xacro
There are en dash in: *description/urdf/snippets.xacro uuv_simulator/uuv_assistants/templates/robot_model/urdf/snippets.xacro.template uuv_simulator/uuv_tutorials/uuv_tutorial_rov_model/urdf/rov_example_snippets.xacro
Hi @hbaqueiro is this issue still makes sense? Can we close it?
Hi everyone,
(I'm a beginner to ROS, Gazebo and UUV Simulator) I am doing the tutorial of UUV Simulator and in the section "Configuring the thruster manager for a new vehicle" I am getting the following error when I try to include my vehicle into the world:
Can anyone help me? Thanks in advance :)