Skip to content

Commit

Permalink
Merge branch 'main' into feat/add-setup-gazebo
Browse files Browse the repository at this point in the history
Signed-off-by: Saurabh Kamat <kamatsaurabh01@gmail.com>
  • Loading branch information
sauk2 committed Nov 4, 2024
2 parents d9fe1af + e8e95b6 commit 6c8c120
Show file tree
Hide file tree
Showing 7 changed files with 35 additions and 9 deletions.
26 changes: 17 additions & 9 deletions config/gazebo-iris-gimbal.parm
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@ FRAME_TYPE 1
MOT_PWM_MIN 1100
MOT_PWM_MAX 1900

# Gimbal on mount 1 has 3 DOF
MNT1_TYPE 1 # Servo
# Servo gimbal on mount 1 has 3 DOF
MNT1_TYPE 1
MNT1_PITCH_MAX 45
MNT1_PITCH_MIN -135
MNT1_ROLL_MAX 30
Expand All @@ -18,15 +18,23 @@ MNT1_YAW_MIN -160
# Gimbal RC in
RC6_MAX 1900
RC6_MIN 1100
RC6_OPTION 212 # Mount1 Roll

# Mount1 Roll
RC6_OPTION 212

# Mount1 Pitch
RC7_MAX 1900
RC7_MIN 1100
RC7_OPTION 213 # Mount1 Pitch
RC7_OPTION 213

# Mount1 Yaw
RC8_MAX 1900
RC8_MIN 1100
RC8_OPTION 214 # Mount1 Yaw
RC8_OPTION 214

# Gimbal servo out
SERVO9_FUNCTION 8 # Mount1Roll
SERVO10_FUNCTION 7 # Mount1Pitch
SERVO11_FUNCTION 6 # Mount1Yaw
# Mount1Roll
SERVO9_FUNCTION 8
# Mount1Pitch
SERVO10_FUNCTION 7
# Mount1Yaw
SERVO11_FUNCTION 6
6 changes: 6 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,12 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>rapidjson-dev</build_depend>
<build_depend>libopencv-dev</build_depend>
<build_depend>libgstreamer1.0-dev</build_depend>
<build_depend>libgstreamer-plugins-base1.0-dev</build_depend>
<build_depend>gstreamer1.0-plugins-bad</build_depend>
<build_depend>gstreamer1.0-libav</build_depend>
<build_depend>gstreamer1.0-gl</build_depend>

<!-- Harmonic (default) -->
<depend condition="$GZ_VERSION == harmonic">gz-cmake3</depend>
Expand Down
2 changes: 2 additions & 0 deletions src/ArduPilotPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,10 @@
#include <gz/msgs/imu.pb.h>
#include <gz/msgs/laserscan.pb.h>

#include <algorithm>
#include <chrono>
#include <functional>
#include <memory>
#include <mutex>
#include <string>
#include <sstream>
Expand Down
2 changes: 2 additions & 0 deletions src/CameraZoomPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,10 @@
#include <atomic>
#include <cmath>
#include <limits>
#include <memory>
#include <mutex>
#include <string>
#include <vector>

#include <gz/common/Profiler.hh>

Expand Down
2 changes: 2 additions & 0 deletions src/GstCameraPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,10 @@
#include <gst/gst.h>

#include <iostream>
#include <memory>
#include <string>
#include <thread>
#include <vector>

#include <gz/plugin/Register.hh>
#include <gz/rendering/Camera.hh>
Expand Down
2 changes: 2 additions & 0 deletions src/ParachutePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,9 @@

#include <gz/msgs/entity_factory.pb.h>

#include <memory>
#include <string>
#include <vector>

#include <gz/plugin/Register.hh>
#include <gz/common/Profiler.hh>
Expand Down
4 changes: 4 additions & 0 deletions src/Util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,10 @@

#include "Util.hh"

#include <string>
#include <unordered_set>
#include <vector>

#include <gz/sim/components/Joint.hh>
#include <gz/sim/components/JointVelocity.hh>
#include <gz/sim/components/Name.hh>
Expand Down

0 comments on commit 6c8c120

Please sign in to comment.