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

Dual redundant fc #731

Closed
wants to merge 15 commits into from
Closed
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
3 changes: 3 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -94,3 +94,6 @@
[submodule "Tools/simulation/gz/plugins/px4-gzsim-plugins"]
path = Tools/simulation/gz/plugins/px4-gzsim-plugins
url = https://github.com/tiiuae/px4-gzsim-plugins.git
[submodule "src/modules/redundancy"]
path = src/modules/redundancy
url = [email protected]:tiiuae/px4_redundancy.git
6 changes: 6 additions & 0 deletions Tools/simulation/gz/hitl_run.sh
Original file line number Diff line number Diff line change
@@ -1,10 +1,16 @@
#!/bin/bash

GZ_SIM_SYSTEM_PLUGIN_PATH=$(pwd)/build/px4_sitl_default/build_gz-sim_plugins/
PX4_GZ_MODELS=$(pwd)/Tools/simulation/gz/models
PX4_GZ_WORLDS=$(pwd)/Tools/simulation/gz/worlds

#example for run
#./Tools/simulation/gz/hitl_run.sh x500/model_hitl.sdf

MODEL_PATH=$1



if [ -z $MODEL_PATH ]; then
echo "You should specify a path to the using model"
echo "./Tools/simulation/gz/hitl_run.sh x500/model_hitl.sdf"
Expand Down
289 changes: 0 additions & 289 deletions Tools/simulation/gz/models/ssrc_holybro_x500/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -605,256 +605,6 @@
</plugin>
<!--} END MOTOR PLUGINS -->

<!-- THIRD PERSON CAMERA {-->
<link name="camera_link">
<kinematic>1</kinematic>
<pose>-2 0 1 0 0.3 0</pose>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.0</ixx>
<iyy>0.0</iyy>
<izz>0.0</izz>
</inertia>
</inertial>
<sensor type="camera" name="third-person-camera">
<camera>
<horizontal_fov>1.7</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
</image>
<clip>
<near>0.1</near>
<far>1000</far>
</clip>
</camera>
<always_on>true</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
<joint name='camera_joint' type='fixed'>
<kinematic>1</kinematic>
<child>camera_link</child>
<parent>base_link</parent>
<axis>
<xyz>50 -50 50</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<!--} END THIRD PERSON CAMERA -->

<!-- GIMBAL CAMERA {-->
<link name="gimbal_camera_link">
<pose>0 0 0 0 1.57 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.01 0.01 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.01 0.01 0.01</size>
</box>
</geometry>
</visual>
<sensor type="camera" name="onboard-gimbal-camera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>true</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
<joint name='camera_joint_tilt' type='revolute'>
<child>gimbal_camera_link</child>
<parent>camera_link_pan</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<link name="camera_link_pan">
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<empty/>
</geometry>
<transparency>1</transparency>
</visual>
<collision name="collision">
<geometry>
<empty/>
</geometry>
</collision>
</link>
<joint name='camera_joint_pan' type='revolute'>
<child>camera_link_pan</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<!--} END GIMBAL CAMERA -->

<!-- RP LIDAR {-->
<link name="2d_scanner_link">
<pose>0 0 0.089 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>
<sensor name="rplidar" type="gpu_lidar">
<always_on>true</always_on>
<update_rate>20</update_rate>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-3.1241390751</min_angle>
<max_angle>3.1241390751</max_angle>
</horizontal>
</scan>
<range>
<min>0.15</min>
<max>14</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
</sensor>
<visual name='rplidar_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/x500_rplidar.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='2d_scanner_joint' type='fixed'>
<child>2d_scanner_link</child>
<parent>base_link</parent>
</joint>
<!--} END RP LIDAR -->

<!-- GARMIN RANGEFINDER {-->
<link name="lidar0_link">
<pose>-0.007 -0.04 -0.039 0 1.5708 1.5708</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>
<visual name='garmin_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>meshes/garmin_lidar_v3.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Black</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<sensor name="garmin" type="gpu_lidar">
<always_on>true</always_on>
<update_rate>100</update_rate>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>-0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.06</min> <!-- do not change: use min_distance (below) for realistic behavior (smaller values cause issues) -->
<max>35</max> <!-- do not change: use max_distance (below) for realistic behavior (bigger values cause issues) -->
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<!-- <plugin name="drone-placeholder-1_garmin" filename="libgazebo_lidar_plugin.so"> -->
<!-- <robotNamespace></robotNamespace> -->
<!-- <min_distance>0.1</min_distance> -->
<!-- <max_distance>30.0</max_distance> -->
<!-- </plugin> -->
</sensor>
</link>
<!-- name of the link for garmin has to contain lidar word to be detected by mavlink gazebo plugin -->
<joint name='lidar0_joint' type='fixed'>
<child>lidar0_link</child>
<parent>base_link</parent>
</joint>
<!--} END GARMIN RANGEFINDER -->

<plugin
filename="gz-sim-pose-publisher-system"
name="gz::sim::systems::PosePublisher">
Expand All @@ -871,45 +621,6 @@
<dimensions>3</dimensions>
</plugin>

<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>camera_joint_pan</joint_name>
<p_gain>1</p_gain>
<i_gain>0.1</i_gain>
<d_gain>0.01</d_gain>
<i_max>1</i_max>
<i_min>-1</i_min>
<cmd_max>1000</cmd_max>
<cmd_min>-1000</cmd_min>
</plugin>

<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>camera_joint_tilt</joint_name>
<p_gain>1</p_gain>
<i_gain>0.1</i_gain>
<d_gain>0.01</d_gain>
<i_max>1</i_max>
<i_min>-1</i_min>
<cmd_max>1000</cmd_max>
<cmd_min>-1000</cmd_min>
</plugin>

<plugin
filename="gz-sim-joint-state-publisher-system"
name="gz::sim::systems::JointStatePublisher">
<joint_name>camera_joint_pan</joint_name>
</plugin>

<plugin
filename="gz-sim-joint-state-publisher-system"
name="gz::sim::systems::JointStatePublisher">
<joint_name>camera_joint_tilt</joint_name>
</plugin>


<!--} END PLUGINS -->
</model>
</sdf>
8 changes: 5 additions & 3 deletions Tools/simulation/gz/models/ssrc_holybro_x500/model_hitl.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,12 @@
<robotNamespace/>
<imuSubTopic>/link/base_link/sensor/imu_sensor/imu</imuSubTopic>
<poseSubTopic>/pose/info</poseSubTopic>
<mavlink_addr>192.168.200.101</mavlink_addr>
<mavlink_udp_local_port>14542</mavlink_udp_local_port>
<mavlink_udp_remote_port>14543</mavlink_udp_remote_port>
<mavlink_addr>192.168.202.1</mavlink_addr>
<mavlink_udp_local_port>14561</mavlink_udp_local_port>
<mavlink_udp_remote_port>14560</mavlink_udp_remote_port>
<mavlink_tcp_port>4560</mavlink_tcp_port>
<secondary_mavlink_addr>192.168.202.65</secondary_mavlink_addr>
<secondary_mavlink_udp_local_port>14562</secondary_mavlink_udp_local_port>
<use_tcp>0</use_tcp>
</plugin>
</model>
Expand Down
2 changes: 1 addition & 1 deletion boards/ssrc/saluki-pi
1 change: 1 addition & 0 deletions clone_public.sh
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ do
[[ "${repo}" == *pfsoc_crypto ]] || \
[[ "${repo}" == *pfsoc_keystore ]] || \
[[ "${repo}" == *pf_crypto ]] || \
[[ "${repo}" == src/modules/redundancy ]] || \
[[ "${repo}" == *process ]] && continue
git submodule update --init --recursive "${repo}"
done <<< "$(git submodule status | awk '{print $2}')"
1 change: 1 addition & 0 deletions msg/ActuatorOutputs.msg
Original file line number Diff line number Diff line change
Expand Up @@ -6,3 +6,4 @@ float32[16] output # output data, in natural output units

# actuator_outputs_sim is used for SITL, HITL & SIH (with an output range of [-1, 1])
# TOPICS actuator_outputs actuator_outputs_sim actuator_outputs_debug
# TOPICS redundant_actuator_outputs0 redundant_actuator_outputs1
5 changes: 5 additions & 0 deletions msg/VehicleStatus.msg
Original file line number Diff line number Diff line change
Expand Up @@ -122,3 +122,8 @@ bool calibration_enabled

bool pre_flight_checks_pass # true if all checks necessary to arm pass

# Maximum number of redundant (backup) flight controllers
uint8 MAX_REDUNDANT_CONTROLLERS = 2

# TOPICS vehicle_status
# TOPICS redundant_status0 redundant_status1
Loading