Compare commits
2 Commits
59fc76711c
...
624a08af63
Author | SHA1 | Date |
---|---|---|
cesar | 624a08af63 | |
cesar | 82fc59ed33 |
|
@ -18,6 +18,7 @@ param set-default MC_PITCHRATE_I 0.15
|
|||
#param load spiri_param/Vehicle_230_Parameters.params
|
||||
|
||||
param set-default MPC_Z_VEL_MAX_UP 1.0
|
||||
param set-default COM_RCL_EXCEPT 4
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
|
|
@ -7,16 +7,18 @@
|
|||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
param set MC_ROLLRATE_K 2.35
|
||||
param set MC_ROLLRATE_D 0.0030
|
||||
param set MC_ROLLRATE_I 0.15
|
||||
param set-default MC_ROLLRATE_K 2.35
|
||||
param set-default MC_ROLLRATE_D 0.0030
|
||||
param set-default MC_ROLLRATE_I 0.15
|
||||
|
||||
param set MC_PITCHRATE_K 2.35
|
||||
param set MC_PITCHRATE_D 0.0030
|
||||
param set MC_PITCHRATE_I 0.15
|
||||
param set-default MC_PITCHRATE_K 2.35
|
||||
param set-default MC_PITCHRATE_D 0.0030
|
||||
param set-default MC_PITCHRATE_I 0.15
|
||||
|
||||
param set MPC_Z_VEL_MAX_UP 0.5
|
||||
param set MPC_TKO_SPEED 1.0
|
||||
param set-default MPC_Z_VEL_MAX_UP 0.5
|
||||
param set-default MPC_TKO_SPEED 1.0
|
||||
|
||||
param set-default COM_RCL_EXCEPT 4
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
|
|
@ -12,7 +12,6 @@
|
|||
<arg name="pluginlists_yaml" default="$(find oscillation_ctrl)/config/px4_pluginlists.yaml" />
|
||||
<arg name="config_yaml" default="$(find oscillation_ctrl)/config/px4_config.yaml" />
|
||||
|
||||
|
||||
<include file="$(find mavros)/launch/node.launch">
|
||||
<arg name="pluginlists_yaml" value="$(arg pluginlists_yaml)" />
|
||||
<arg name="config_yaml" value="$(arg config_yaml)" />
|
||||
|
|
|
@ -7,6 +7,7 @@
|
|||
<inertial>
|
||||
<pose frame=''>0 0.00268 -0.000742 0 -0 0</pose>
|
||||
<mass>1.437</mass>
|
||||
<!--mass>0.5841</mass-->
|
||||
<inertia>
|
||||
<ixx>0.1152</ixx>
|
||||
<ixy>0</ixy>
|
||||
|
@ -473,7 +474,7 @@
|
|||
<child>sonar_link</child>
|
||||
</joint-->
|
||||
<!--px4flow camera-->
|
||||
<include>
|
||||
<!--include>
|
||||
<uri>model://px4flow</uri>
|
||||
<pose>0.05 0 -0.05 0 0 0</pose>
|
||||
</include>
|
||||
|
@ -488,9 +489,9 @@
|
|||
<lower>0</lower>
|
||||
</limit>
|
||||
</axis>
|
||||
</joint>
|
||||
</joint-->
|
||||
|
||||
<!--lidar-->
|
||||
<!--lidar>
|
||||
<include>
|
||||
<uri>model://lidar</uri>
|
||||
<pose>0 0 -0.05 0 0 0</pose>
|
||||
|
@ -499,7 +500,7 @@
|
|||
<joint name="lidar_joint" type="fixed">
|
||||
<parent>spiri::base</parent>
|
||||
<child>lidar::link</child>
|
||||
</joint>
|
||||
</joint-->
|
||||
<plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
|
||||
<robotNamespace/>
|
||||
<linkName>base</linkName>
|
||||
|
|
Loading…
Reference in New Issue