remove unneeded parameters

This commit is contained in:
John Hsu 2016-08-24 16:34:45 -07:00
parent 28fad534d2
commit 076892a334

View File

@ -514,7 +514,7 @@
<link_name>iris::rotor_3</link_name>
</plugin>
<plugin name="arducopter_plugin" filename="libArduCopterPlugin.so">
<imuLinkName>iris::iris/imu_link</imuLinkName>
<imuName>iris::iris/imu_link::imu_sensor</imuName>
<connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
<rotor id="0">
<vel_p_gain>0.2</vel_p_gain>
@ -525,9 +525,7 @@
<vel_cmd_max>2.0</vel_cmd_max>
<vel_cmd_min>-2.0</vel_cmd_min>
<jointName>iris::rotor_0_joint</jointName>
<linkName>iris::rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<motorNumber>0</motorNumber>
<rotorVelocitySlowdownSim>1</rotorVelocitySlowdownSim>
</rotor>
<rotor id="1">
@ -539,9 +537,7 @@
<vel_cmd_max>2.0</vel_cmd_max>
<vel_cmd_min>-2.0</vel_cmd_min>
<jointName>iris::rotor_1_joint</jointName>
<linkName>iris::rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<motorNumber>1</motorNumber>
<rotorVelocitySlowdownSim>1</rotorVelocitySlowdownSim>
</rotor>
<rotor id="2">
@ -553,9 +549,7 @@
<vel_cmd_max>2.0</vel_cmd_max>
<vel_cmd_min>-2.0</vel_cmd_min>
<jointName>iris::rotor_2_joint</jointName>
<linkName>iris::rotor_2</linkName>
<turningDirection>cw</turningDirection>
<motorNumber>2</motorNumber>
<rotorVelocitySlowdownSim>1</rotorVelocitySlowdownSim>
</rotor>
<rotor id="3">
@ -567,9 +561,7 @@
<vel_cmd_max>2.0</vel_cmd_max>
<vel_cmd_min>-2.0</vel_cmd_min>
<jointName>iris::rotor_3_joint</jointName>
<linkName>iris::rotor_3</linkName>
<turningDirection>cw</turningDirection>
<motorNumber>3</motorNumber>
<rotorVelocitySlowdownSim>1</rotorVelocitySlowdownSim>
</rotor>
</plugin>