From c20422dc7e8758927794eb66c94db75cac1cf838 Mon Sep 17 00:00:00 2001 From: isvogor Date: Wed, 15 Feb 2017 16:36:22 -0500 Subject: [PATCH] init branch --- .gitignore | 2 ++ launch/launch_config/m100.yaml | 8 ++++++++ launch/launch_config/solo.yaml | 12 ++++++++++++ launch/rosbuzz.launch | 19 +++++++++++++++++++ 4 files changed, 41 insertions(+) create mode 100644 launch/launch_config/m100.yaml create mode 100644 launch/launch_config/solo.yaml create mode 100644 launch/rosbuzz.launch diff --git a/.gitignore b/.gitignore index a7c46f8..7d62213 100644 --- a/.gitignore +++ b/.gitignore @@ -1 +1,3 @@ src/test* +.cproject +.project diff --git a/launch/launch_config/m100.yaml b/launch/launch_config/m100.yaml new file mode 100644 index 0000000..5950785 --- /dev/null +++ b/launch/launch_config/m100.yaml @@ -0,0 +1,8 @@ +topics: + gps : /global_position + battery : /power_status + status : /flight_status +type: + gps : sensor_msgs/NavSatFix + battery : mavros_msgs/BatteryStatus + status : mavros_msgs/ExtendedState \ No newline at end of file diff --git a/launch/launch_config/solo.yaml b/launch/launch_config/solo.yaml new file mode 100644 index 0000000..f7e47c1 --- /dev/null +++ b/launch/launch_config/solo.yaml @@ -0,0 +1,12 @@ +topics: + gps : /mavros/global_position/global + battery : /mavros/battery + status : /mavros/state +type: + gps : sensor_msgs/NavSatFix + # for SITL Solo + battery : mavros_msgs/BatteryState + # for solo + #battery : mavros_msgs/BatteryStatus + status : mavros_msgs/State + diff --git a/launch/rosbuzz.launch b/launch/rosbuzz.launch new file mode 100644 index 0000000..31df5c1 --- /dev/null +++ b/launch/rosbuzz.launch @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + +