Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Iris: update iris_with_gimbal model to 3d gimbal #102

Merged
merged 6 commits into from
Jul 7, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
52 changes: 29 additions & 23 deletions config/gazebo-iris-gimbal.parm
Original file line number Diff line number Diff line change
Expand Up @@ -2,29 +2,35 @@
FRAME_CLASS 1
FRAME_TYPE 1

# IRLOCK FEATURE
RC8_OPTION 39
PLND_ENABLED 1
PLND_TYPE 3
# Match servo out for motors
MOT_PWM_MIN 1100
MOT_PWM_MAX 1900

# SONAR FOR IRLOCK
SIM_SONAR_SCALE 10
RNGFND1_TYPE 1
RNGFND1_SCALING 10
RNGFND1_PIN 0
RNGFND1_MAX_CM 5000
# Gimbal on mount 1 has 3 DOF
MNT1_TYPE 1 # Servo
MNT1_PITCH_MAX 45
MNT1_PITCH_MIN -135
MNT1_ROLL_MAX 30
MNT1_ROLL_MIN -30
MNT1_YAW_MAX 160
MNT1_YAW_MIN -160

# Gimbal on mount 1 has 2 DOF
MNT1_PITCH_MAX 90
MNT1_PITCH_MIN -90
MNT1_ROLL_MAX 90
MNT1_ROLL_MIN -90
MNT1_TYPE 1
# Gimbal RC in
RC6_MAX 1900
RC6_MIN 1100
RC6_OPTION 212 # Mount1 Roll
RC7_MAX 1900
RC7_MIN 1100
RC7_OPTION 213 # Mount1 Pitch
RC8_MAX 1900
RC8_MIN 1100
RC8_OPTION 214 # Mount1 Yaw
RC8_REVERSED 0 # Normal
RC9_MAX 1900
RC9_MIN 1100
RC9_OPTION 0 # Do Nothing

# Gimbal roll and pitch RC
RC9_OPTION 212
RC10_OPTION 213

# Gimbal roll and pitch servos
SERVO5_FUNCTION 8
SERVO6_FUNCTION 7
# Gimbal servo out
SERVO9_FUNCTION 8 # Mount1Roll
SERVO10_FUNCTION 7 # Mount1Pitch
SERVO11_FUNCTION 6 # Mount1Yaw
6 changes: 3 additions & 3 deletions models/gimbal_small_1d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -140,11 +140,11 @@
<axis>
<xyz>1 0 0</xyz>
<dynamics>
<damping>0.5</damping>
<damping>0.01</damping>
</dynamics>
<limit>
<lower>-1.57079632</lower>
<upper>1.57079632</upper>
<lower>-3.1415926</lower>
<upper>3.1415926</upper>
</limit>
</axis>
<pose>0 0 0.02 0 0 0</pose>
Expand Down
12 changes: 6 additions & 6 deletions models/gimbal_small_2d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -76,11 +76,11 @@
<axis>
<xyz>0 0 1</xyz>
<dynamics>
<damping>0.5</damping>
<damping>0.01</damping>
</dynamics>
<limit>
<lower>-1.57079632</lower>
<upper>1.57079632</upper>
<lower>-3.1415926</lower>
<upper>3.1415926</upper>
</limit>
</axis>
<pose>0.01 0 -0.04 0 0 0</pose>
Expand Down Expand Up @@ -176,11 +176,11 @@
<axis>
<xyz>1 0 0</xyz>
<dynamics>
<damping>0.5</damping>
<damping>0.01</damping>
</dynamics>
<limit>
<lower>-1.57079632</lower>
<upper>1.57079632</upper>
<lower>-3.1415926</lower>
<upper>3.1415926</upper>
</limit>
</axis>
<pose>0 0 0.02 0 0 0</pose>
Expand Down
18 changes: 9 additions & 9 deletions models/gimbal_small_3d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -74,11 +74,11 @@
<axis>
<xyz>0 1 0</xyz>
<dynamics>
<damping>0.5</damping>
<damping>0.01</damping>
</dynamics>
<limit>
<lower>-1.57079632</lower>
<upper>1.57079632</upper>
<lower>-3.1415926</lower>
<upper>3.1415926</upper>
</limit>
</axis>
<pose>0.0105 0.065 -0.002 0 0 0</pose>
Expand Down Expand Up @@ -122,11 +122,11 @@
<axis>
<xyz>0 0 1</xyz>
<dynamics>
<damping>0.5</damping>
<damping>0.01</damping>
</dynamics>
<limit>
<lower>-1.57079632</lower>
<upper>1.57079632</upper>
<lower>-3.1415926</lower>
<upper>3.1415926</upper>
</limit>
</axis>
<pose>0.0099 0.002 -0.05 0 0 0</pose>
Expand Down Expand Up @@ -227,11 +227,11 @@
<axis>
<xyz>1 0 0</xyz>
<dynamics>
<damping>0.5</damping>
<damping>0.01</damping>
</dynamics>
<limit>
<lower>-1.57079632</lower>
<upper>1.57079632</upper>
<lower>-3.1415926</lower>
<upper>3.1415926</upper>
</limit>
</axis>
<pose>0.045 0.0021 0.0199 0 0 0</pose>
Expand Down
43 changes: 32 additions & 11 deletions models/iris_with_gimbal/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
</include>

<include>
<uri>model://gimbal_small_2d</uri>
<uri>model://gimbal_small_3d</uri>
<name>gimbal</name>
<pose degrees="true">0 -0.01 -0.124923 90 0 90</pose>
</include>
Expand Down Expand Up @@ -280,26 +280,40 @@
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
</control>

<control channel="4">
<!-- roll range is -30 to +30 deg -->
<control channel="8">
<jointName>gimbal::roll_joint</jointName>
<multiplier>3.14159265</multiplier>
<multiplier>1.047197551196</multiplier>
<offset>-0.5</offset>
<servo_min>1100</servo_min>
<servo_max>1900</servo_max>
<type>COMMAND</type>
<cmd_topic>/gimbal/cmd_roll</cmd_topic>
<p_gain>3</p_gain>
<p_gain>2</p_gain>
</control>

<control channel="5">
<jointName>gimbal::tilt_joint</jointName>
<multiplier>3.14159265</multiplier>
<!-- pitch range is -135 to +45 deg -->
<control channel="9">
<jointName>gimbal::pitch_joint</jointName>
<multiplier>-3.14159265</multiplier>
<offset>-0.75</offset>
<servo_min>1100</servo_min>
<servo_max>1900</servo_max>
<type>COMMAND</type>
<cmd_topic>/gimbal/cmd_pitch</cmd_topic>
<p_gain>2</p_gain>
</control>

<!-- yaw range is -160 to +160 deg -->
<control channel="10">
<jointName>gimbal::yaw_joint</jointName>
<multiplier>-5.5850536</multiplier>
<offset>-0.5</offset>
<servo_min>1100</servo_min>
<servo_max>1900</servo_max>
<type>COMMAND</type>
<cmd_topic>/gimbal/cmd_tilt</cmd_topic>
<p_gain>3</p_gain>
<cmd_topic>/gimbal/cmd_yaw</cmd_topic>
<p_gain>2</p_gain>
</control>

</plugin>
Expand All @@ -314,8 +328,15 @@
<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>gimbal::tilt_joint</joint_name>
<topic>/gimbal/cmd_tilt</topic>
<joint_name>gimbal::pitch_joint</joint_name>
<topic>/gimbal/cmd_pitch</topic>
<p_gain>2</p_gain>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>gimbal::yaw_joint</joint_name>
<topic>/gimbal/cmd_yaw</topic>
<p_gain>2</p_gain>
</plugin>

Expand Down
2 changes: 1 addition & 1 deletion worlds/iris_runway.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@
</include>

<include>
<uri>model://iris_with_ardupilot</uri>
<uri>model://iris_with_gimbal</uri>
<pose degrees="true">0 0 0.195 0 0 90</pose>
</include>

Expand Down
2 changes: 1 addition & 1 deletion worlds/iris_warehouse.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,7 @@

<include>
<pose>-6 0 0.25 0 0 0</pose>
<uri>model://iris_with_ardupilot</uri>
<uri>model://iris_with_gimbal</uri>
</include>

<include>
Expand Down
Loading