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

Add generated code and takeoff example #71

Open
wants to merge 4 commits into
base: develop
Choose a base branch
from
Open
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
91 changes: 69 additions & 22 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,57 +3,104 @@
This is the Rust wrapper for MAVSDK.

The Rust wrapper is based on a gRPC client communicating with the gRPC server written in C++.
The wrapper is potentially auto-generated from the message definitions ([proto files](https://github.com/mavlink/MAVSDK-Proto)).
The wrapper is auto-generated from the message definitions ([proto files](https://github.com/mavlink/MAVSDK-Proto)).

# Update Rust for async/await support (first time)
```bash
$ rustup update
```
## Requirements

- Rust >= 1.39.0 (for async/await support)
- Building mavsdk-rust requires the [protoc](https://grpc.io/docs/protoc-installation/) compiler to be installed.

# Build
## Trying the Examples

*note that building mavsdk-rust requires the [protoc](https://grpc.io/docs/protoc-installation/) compiler to be installed.*
1. Initialize proto submodule and build

```bash
$ cargo build
git submodule init
git submodule update
cargo build
```

# Run examples
2. Start a simulator as described [here.](https://mavsdk.mavlink.io/main/en/cpp/examples/#setting-up-a-simulator)

1. Run **MAVSDK Backend** on `localhost:50051`
2. Run examples
```bash
$ cargo run --example info
make px4_sitl jmavsim
```

3. Run **MAVSDK Backend** on `localhost:50051`. [More info here.](https://mavsdk.mavlink.io/main/en/cpp/guide/build_mavsdk_server.html)

```bash
$ cargo run --example mocap
cd [path_to_MAVSDK]
./build/default/src/mavsdk_server/src/mavsdk_server
```

4. Run examples

- Info

```bash
$ cargo run --example telemetry
cargo run --example info

```

# Expected examples output
Expected output:

- `info`
```bash
$ cargo run --example info
Finished dev [unoptimized + debuginfo] target(s) in 0.01s
Running `target/debug/examples/info`
Version received: Version { flight_sw_major: 1, flight_sw_minor: 10, flight_sw_patch: 0, flight_sw_vendor_major: 0, flight_sw_vendor_minor: 0, flight_sw_vendor_patch: 0, os_sw_major: 8, os_sw_minor: 2, os_sw_patch: 0 }
```
- `mocap`

- Mocap

```bash
cargo run --example mocap
```

Expected output:

```bash
$ cargo run --example mocap
Finished dev [unoptimized + debuginfo] target(s) in 0.31s
Running `target/debug/examples/mocap`
All sended successfully!
...
Sending SetVisionPositionEstimateRequest { vision_position_estimate: Some(VisionPositionEstimate { time_usec: 0, position_body: Some(PositionBody { x_m: 49.89981, y_m: -49.89981, z_m: -4.9900193 }), angle_body: Some(AngleBody { roll_rad: 0.0, pitch_rad: 0.0, yaw_rad: 0.0 }), pose_covariance: Some(Covariance { covariance_matrix: [] }) }) }
All sent successfully!
```
- `telemetry`

- Telemetry

```bash
cargo run --example telemery
```

Expected output:

```bash
$ cargo run --example telemery
Compiling libmavsdk v0.1.0 (/home/ildar/sw/mavsdk-rust)
Finished dev [unoptimized + debuginfo] target(s) in 4.92s
Running `target/debug/examples/telemetry`
...
Odometry: Odometry { time_usec: 0, frame_id: EstimNed, child_frame_id: Undef, position_body: PositionBody { x_m: 0.0, y_m: 0.0, z_m: -3.483048 }, q: Quaternion { w: 0.6384722, x: -0.004061609, y: 0.079110526, z: 0.76555747 }, speed_body: SpeedBody { velocity_x_m_s: 0.0042169667, velocity_y_m_s: -0.0015938352, velocity_z_m_s: -0.014632007 }, angular_velocity_body: AngularVelocityBody { roll_rad_s: 0.0005086092, pitch_rad_s: 0.00023366197, yaw_rad_s: -0.0002803828 }, pose_covariance: Covariance { covariance_matrix: [0.0079130605, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007913225, 0.0, 0.0, 0.0, 0.0, 0.044821125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] }, velocity_covariance: Covariance { covariance_matrix: [0.0052988436, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0052990587, 0.0, 0.0, 0.0, 0.0, 0.0045366324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] } }
...
```

- Takeoff and land

```bash
cargo run --example takeoff_and_land

```

Expected output:

```bash
Finished dev [unoptimized + debuginfo] target(s) in 0.02s
Running `target/debug/examples/takeoff_and_land`
Waiting for drone to be ready...
Drone ready to arm!
Start takeoff
Wait 10 seconds and land...
Start landing
Example finished
```

You should see the copter taking off, holding and landing in the sim window.
21 changes: 11 additions & 10 deletions build.rs
Original file line number Diff line number Diff line change
@@ -1,18 +1,18 @@
const PROTO_INCLUDE_PATH: &str = "proto/protos";

const PLUGINS: &[&str] = &[
//"action",
//"calibration",
//"camera",
//"core",
//"geofence",
//"gimbal",
"action",
"calibration",
"camera",
"core",
"geofence",
"gimbal",
"info",
//"mission",
"mission",
"mocap",
//"offboard",
//"param",
//"shell",
"offboard",
"param",
"shell",
"telemetry",
];

Expand All @@ -22,6 +22,7 @@ fn main() -> std::io::Result<()> {

tonic_build::configure()
.build_server(false)
.out_dir("src/grpc/")
.compile(&[proto_path.as_str()], &[PROTO_INCLUDE_PATH])?;
}
Ok(())
Expand Down
19 changes: 6 additions & 13 deletions examples/info.rs
Original file line number Diff line number Diff line change
@@ -1,20 +1,13 @@
use libmavsdk::System;
use std::io::{self, Write};
use libmavsdk::info;

#[tokio::main]
async fn main() -> Result<(), Box<dyn std::error::Error>> {
let args: Vec<String> = std::env::args().skip(1).collect();
let mut version_service =
info::info_service_client::InfoServiceClient::connect("http://0.0.0.0:50051").await?;

if args.len() > 1 {
io::stderr()
.write_all(b"Usage: info [connection_url]\n")
.unwrap();
std::process::exit(1);
}

let url = args.first().cloned();

let version = System::connect(url).await?.info.get_version().await?;
let version = version_service
.get_version(info::GetVersionRequest::default())
.await?;

println!("Version received: {version:?}");

Expand Down
42 changes: 18 additions & 24 deletions examples/mocap.rs
Original file line number Diff line number Diff line change
@@ -1,39 +1,33 @@
use libmavsdk::{mocap, System};
use std::io::{self, Write};
use libmavsdk::mocap;
use std::time::Duration;

#[tokio::main]
async fn main() -> Result<(), Box<dyn std::error::Error>> {
let args: Vec<String> = std::env::args().skip(1).collect();
let mut vision_position_estimate = mocap::VisionPositionEstimate {
time_usec: 0,
position_body: Some(mocap::PositionBody::default()),
angle_body: Some(mocap::AngleBody::default()),
pose_covariance: Some(mocap::Covariance::default()),
};

if args.len() > 1 {
io::stderr()
.write_all(b"Usage: info [connection_url]\n")
.unwrap();
std::process::exit(1);
}

let url = args.first().cloned();

let mut system = System::connect(url).await?;

let mut vision_position_estimate = mocap::VisionPositionEstimate::default();
vision_position_estimate.pose_covariance.covariance_matrix = vec![std::f32::NAN];
let mut mocap_service =
mocap::mocap_service_client::MocapServiceClient::connect("http://0.0.0.0:50051").await?;

for _ in 0..500 {
system
.mocap
.set_vision_position_estimate(vision_position_estimate.clone())
.await?;
let req = mocap::SetVisionPositionEstimateRequest {
vision_position_estimate: Some(vision_position_estimate.clone()),
};
println!("Sending {:?}", req);
mocap_service.set_vision_position_estimate(req).await?;

vision_position_estimate.position_body.x_m += 0.1;
vision_position_estimate.position_body.y_m -= 0.1;
vision_position_estimate.position_body.z_m -= 0.01;
vision_position_estimate.position_body.as_mut().unwrap().x_m += 0.1;
vision_position_estimate.position_body.as_mut().unwrap().y_m -= 0.1;
vision_position_estimate.position_body.as_mut().unwrap().z_m -= 0.01;

tokio::time::sleep(Duration::from_millis(20)).await;
}

println!("All sended successfully!");
println!("All sent successfully!");

Ok(())
}
66 changes: 66 additions & 0 deletions examples/takeoff_and_land.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
use std::process;
use std::thread::sleep;
use std::time::Duration;

use futures_util::StreamExt;
use libmavsdk::action::{self};
use libmavsdk::telemetry;

#[tokio::main]
async fn main() -> Result<(), Box<dyn std::error::Error>> {
let mut telemetry_service =
telemetry::telemetry_service_client::TelemetryServiceClient::connect(
"http://0.0.0.0:50051",
)
.await?;

let mut telemetry_stream = telemetry_service
.subscribe_health(telemetry::SubscribeHealthRequest::default())
.await?
.into_inner();

println!("Waiting for drone to be ready...");
while let Some(odometry) = telemetry_stream.next().await {
if odometry.is_ok() {
break;
}
}
println!("Drone ready to arm!");

let mut action_service =
action::action_service_client::ActionServiceClient::connect("http://0.0.0.0:50051").await?;

let arm_request = action::ArmRequest::default();
let arm_response =
action::action_service_client::ActionServiceClient::arm(&mut action_service, arm_request)
.await?
.into_inner();

// Checking responses example
if let Some(value) = arm_response.action_result {
if !value.result_str.eq("Success") {
println!("Drone armed {:?}", value);
}
} else {
process::exit(1);
}

println!("Start takeoff");
let takeoff_request = action::TakeoffRequest::default();
action::action_service_client::ActionServiceClient::takeoff(
&mut action_service,
takeoff_request,
)
.await?;

println!("Wait 10 seconds and land...");
sleep(Duration::from_millis(10_000));

println!("Start landing");
let land_request = action::LandRequest::default();
action::action_service_client::ActionServiceClient::land(&mut action_service, land_request)
.await?;

println!("Example finished");
Ok(())
}
34 changes: 14 additions & 20 deletions examples/telemetry.rs
Original file line number Diff line number Diff line change
@@ -1,29 +1,23 @@
use futures_util::stream::StreamExt;
use libmavsdk::System;
use std::io::{self, Write};
use futures_util::StreamExt;
use libmavsdk::telemetry;

#[tokio::main]
async fn main() -> Result<(), Box<dyn std::error::Error>> {
let args: Vec<String> = std::env::args().skip(1).collect();

if args.len() > 1 {
io::stderr()
.write_all(b"Usage: telemetry [connection_url]\n")
.unwrap();
std::process::exit(1);
}

let url = args.first().cloned();
let mut telemetry_service =
telemetry::telemetry_service_client::TelemetryServiceClient::connect(
"http://0.0.0.0:50051",
)
.await?;

let mut stream_odometry = System::connect(url)
let mut odometry_stream = telemetry_service
.subscribe_odometry(telemetry::SubscribeOdometryRequest::default())
.await?
.telemetry
.subscribe_odometry()
.await?;
.into_inner();

while let Some(odometry) = stream_odometry.next().await {
println!("Received: {:?}", odometry?);
while let Some(odometry) = odometry_stream.next().await {
let asd = odometry.unwrap();
println!("asd {:?}", asd)
}
println!("Exit");

Ok(())
}
30 changes: 30 additions & 0 deletions src/grpc/mavsdk.options.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
// This file is @generated by prost-build.
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
#[repr(i32)]
pub enum AsyncType {
Async = 0,
Sync = 1,
Both = 2,
}
impl AsyncType {
/// String value of the enum field names used in the ProtoBuf definition.
///
/// The values are not transformed in any way and thus are considered stable
/// (if the ProtoBuf definition does not change) and safe for programmatic use.
pub fn as_str_name(&self) -> &'static str {
match self {
AsyncType::Async => "ASYNC",
AsyncType::Sync => "SYNC",
AsyncType::Both => "BOTH",
}
}
/// Creates an enum from field names used in the ProtoBuf definition.
pub fn from_str_name(value: &str) -> ::core::option::Option<Self> {
match value {
"ASYNC" => Some(Self::Async),
"SYNC" => Some(Self::Sync),
"BOTH" => Some(Self::Both),
_ => None,
}
}
}
Loading
Loading