use std::time; mod msg { rosrust::rosmsg_include!(roscpp_tutorials / TwoInts); } fn main() { env_logger::init(); // Fetch args that are not meant for rosrust let args: Vec<_> = rosrust::args(); if args.len() != 3 { eprintln!("usage: client X Y"); return; } let a = args[1].parse::().unwrap(); let b = args[2].parse::().unwrap(); // Initialize node rosrust::init("add_two_ints_client"); // Wait ten seconds for the service to appear rosrust::wait_for_service("add_two_ints", Some(time::Duration::from_secs(10))).unwrap(); // Create client for the service let client = rosrust::client::("add_two_ints").unwrap(); // Synchronous call that blocks the thread until a response is received rosrust::ros_info!( "{} + {} = {}", a, b, client .req(&msg::roscpp_tutorials::TwoIntsReq { a, b }) .unwrap() .unwrap() .sum ); // Asynchronous call that can be resolved later on let retval = client.req_async(msg::roscpp_tutorials::TwoIntsReq { a, b }); rosrust::ros_info!("{} + {} = {}", a, b, retval.read().unwrap().unwrap().sum); }