Commit 6fbd1208c699ba279631561987ccead0a180b21d

Authored by Ricardo Rico Uribe
1 parent 5140bb7f

final touches and fixes - error in ardupilot-gazebo plugin

README.md
... ... @@ -12,8 +12,8 @@ Repository to simulate the Aquanaute boat in maritime conditions such as wind an
12 12  
13 13 ### ardupilot parameters
14 14  
15   -in the file "vehiculeinfo.py" (/ardupilot/Tools/autotest/pysim) you need to change the default parameters file for the "gazebo-rover" in line 280 to the aquanaute.parm file provided in /aquanaute/aquanaute_description/ardu_params you can copy and paste the file in the default_params folder located inside (/ardupilot/Tools/autotest).
16   -*There is an error when you launch ardupilot, the motors in the gazebo simulation will start to turn in a fixed direction and wont respond to commands, this issue has not yet been fixed and it's root cause it's not yet defined, it may be the ardupilot_gazebo plugin or the ardupilot frame*
  15 +in the file "vehiculeinfo.py" (/ardupilot/Tools/autotest/pysim) you need to change the default parameters file for the "gazebo-rover" in the line 280 to the aquanaute.parm file provided in /aquanaute/aquanaute_description/ardu_params you can copy and paste the file in the default_params folder located inside (/ardupilot/Tools/autotest).
  16 +*There is an error when you launch ardupilot, the motors in the gazebo simulation will start to turn in a fixed direction and wont respond to commands, this issue has not yet been fixed and it's root cause has not yet been found, It's believed that the ardupilot-gazebo plugin doesnt know how to interpret the signals sended by ardupilot*
17 17  
18 18 ---
19 19  
... ... @@ -58,7 +58,8 @@ then launch the file you created
58 58  
59 59 roslaunch aquanaute_gazebo aquanaute.launch testing:=false
60 60  
61   -this parameter can be changed to true to deactivate the plugins from vrx (the world will be changed to an empty world without gravity)
  61 +this parameter can be changed to true to deactivate the plugins from vrx (the world will be changed to an empty world without gravity).
  62 +You will have an error "Missing Model.../dock_permutations) this is normal.
62 63  
63 64 #### ardupilot
64 65  
... ...
aquanaute_description/ardu_params/aquanaute.parm
1   -FRAME_CLASS 2
2   -AHRS_ORIENTATIONM 0
3   -GCS_PID_MASK 1
4   -SERVO1_FUNCTION 26
5   -SERVO3_FUNCTION 70
6   -ARMING_CHECK 0
  1 +ACRO_TURN_RATE,120
  2 +ARMING_CHECK,0
  3 +CRUISE_SPEED,2
  4 +CRUISE_THROTTLE,20
  5 +FRAME_CLASS,2
  6 +SERVO1_FUNCTION,26
  7 +SERVO1_MAX,1900
  8 +SERVO1_MIN,1100
  9 +SERVO1_REVERSED,1
  10 +SERVO1_TRIM,1500
  11 +SERVO3_FUNCTION,70
  12 +SERVO3_MAX,1900
  13 +SERVO3_MIN,1100
  14 +SERVO3_REVERSED,0
  15 +SERVO3_TRIM,1500
  16 +SPEED_TURN_GAIN,50
  17 +TURN_MAX_G,0.4
  18 +WP_SPEED,4
... ...
aquanaute_gazebo/urdf/aquanaute_gazebo.urdf.xacro
... ... @@ -82,14 +82,28 @@
82 82  
83 83 <control channel="0">
84 84 <type>POSITION</type>
85   - <multiplier>1</multiplier>
  85 + <multiplier>100</multiplier> <!--ARBITRARY VALUES-->
86 86 <offset>0</offset>
  87 + <p_gain>1.0</p_gain>
  88 + <i_gain>0</i_gain>
  89 + <d_gain>0</d_gain>
  90 + <i_max>0</i_max>
  91 + <i_min>0</i_min>
  92 + <cmd_max>3.5</cmd_max>
  93 + <cmd_min>-3.5</cmd_min>
87 94 <jointName>aquanaute::motor_platform_joint</jointName>
88 95 </control>
89   - <control channel="0">
  96 + <control channel="2">
90 97 <type>VELOCITY</type>
91   - <multiplier>1</multiplier>
  98 + <multiplier>800</multiplier> <!--ARBITRARY VALUES-->
92 99 <offset>0</offset>
  100 + <p_gain>0.20</p_gain>
  101 + <i_gain>0</i_gain>
  102 + <d_gain>0</d_gain>
  103 + <i_max>0</i_max>
  104 + <i_min>0</i_min>
  105 + <cmd_max>2.5</cmd_max>
  106 + <cmd_min>-2.5</cmd_min>
93 107 <jointName>aquanaute::propeller_motor_joint</jointName>
94 108 </control>
95 109 <!--
... ...