Make clippy happy

This commit is contained in:
Midnight Exigent 2022-01-07 06:08:01 +01:00
parent f22d29d02f
commit 8a7acc7799
12 changed files with 188 additions and 214 deletions

View File

@ -91,27 +91,24 @@ pub fn get_ros_msgs(paths: &[&Path]) -> Vec<String> {
msgs
}
pub fn parse_msgs(msgs: &Vec<String>) -> Vec<RosMsg> {
pub fn parse_msgs(msgs: &[String]) -> Vec<RosMsg> {
let v: Vec<Vec<&str>> = msgs
.iter()
.map(|l| l.split('/').into_iter().take(3).collect())
.collect();
let v: Vec<_> = v
.iter()
.filter(|v| v.len() == 3)
.map(|v| RosMsg {
module: v[0].into(),
prefix: v[1].into(),
name: v[2].into(),
})
.collect();
// hack because I don't have time to find out the root cause of this at the moment.
// for some reason the library files generated to this are called
// liblibstatistics_collector_test_msgs__..., but I don't know where test_msgs come from.
// (this seems to be a useless package anyway)
// also affects message generation below.
v.into_iter()
v.iter()
.filter(|v| v.len() == 3)
.map(|v| RosMsg {
module: v[0].into(),
prefix: v[1].into(),
name: v[2].into(),
})
.filter(|v| v.module != "libstatistics_collector")
.collect()
}
@ -120,9 +117,9 @@ pub fn as_map(included_msgs: &[RosMsg]) -> HashMap<&str, HashMap<&str, Vec<&str>
let mut msgs = HashMap::new();
for msg in included_msgs {
msgs.entry(msg.module.as_str())
.or_insert(HashMap::new())
.or_insert_with(HashMap::new)
.entry(msg.prefix.as_str())
.or_insert(Vec::new())
.or_insert_with(Vec::new)
.push(msg.name.as_str());
}
msgs
@ -139,7 +136,7 @@ std_msgs/msg/Bool
x/y
std_msgs/msg/String
";
let msgs = msgs.lines().map(|l| l.to_string()).collect();
let msgs = msgs.lines().map(|l| l.to_string()).collect::<Vec<_>>();
let parsed = parse_msgs(&msgs);
assert_eq!(parsed[0].module, "std_msgs");
assert_eq!(parsed[0].prefix, "msg");

View File

@ -3,6 +3,7 @@
#![allow(non_snake_case)]
#![allow(improper_ctypes)]
#![allow(dead_code)]
#![allow(clippy::all)]
include!(concat!(env!("OUT_DIR"), "/msg_bindings.rs"));
include!(concat!(env!("OUT_DIR"), "/introspection_functions.rs"));

View File

@ -145,7 +145,7 @@ where
.upgrade()
.ok_or(Error::RCL_RET_ACTION_CLIENT_INVALID)?;
let mut c = c.lock().unwrap();
c.send_result_request(uuid.clone());
c.send_result_request(uuid);
}
Ok((
@ -177,6 +177,7 @@ where
ActionClient { client }
}
pub type ResultSender<R> = (uuid::Uuid, oneshot::Sender<(GoalStatus, R)>);
pub struct WrappedActionClient<T>
where
T: WrappedActionTypeSupport,
@ -187,7 +188,7 @@ where
Vec<(i64, oneshot::Sender<action_msgs::srv::CancelGoal::Response>)>,
pub feedback_senders: Vec<(uuid::Uuid, mpsc::Sender<T::Feedback>)>,
pub result_requests: Vec<(i64, uuid::Uuid)>,
pub result_senders: Vec<(uuid::Uuid, oneshot::Sender<(GoalStatus, T::Result)>)>,
pub result_senders: Vec<ResultSender<T::Result>>,
pub goal_status: HashMap<uuid::Uuid, GoalStatus>,
pub poll_available_channels: Vec<oneshot::Sender<()>>,
@ -195,18 +196,18 @@ where
pub trait ActionClient_ {
fn handle(&self) -> &rcl_action_client_t;
fn destroy(&mut self, node: &mut rcl_node_t) -> ();
fn destroy(&mut self, node: &mut rcl_node_t);
fn handle_goal_response(&mut self) -> ();
fn handle_cancel_response(&mut self) -> ();
fn handle_feedback_msg(&mut self) -> ();
fn handle_status_msg(&mut self) -> ();
fn handle_result_response(&mut self) -> ();
fn handle_goal_response(&mut self);
fn handle_cancel_response(&mut self);
fn handle_feedback_msg(&mut self);
fn handle_status_msg(&mut self);
fn handle_result_response(&mut self);
fn send_result_request(&mut self, uuid: uuid::Uuid) -> ();
fn send_result_request(&mut self, uuid: uuid::Uuid);
fn register_poll_available(&mut self, s: oneshot::Sender<()>) -> ();
fn poll_available(&mut self, node: &mut rcl_node_t) -> ();
fn register_poll_available(&mut self, s: oneshot::Sender<()>);
fn poll_available(&mut self, node: &mut rcl_node_t);
}
impl<T> WrappedActionClient<T>
@ -273,7 +274,7 @@ where
&self.rcl_handle
}
fn handle_goal_response(&mut self) -> () {
fn handle_goal_response(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut response_msg = WrappedNativeMsg::<
<<T as WrappedActionTypeSupport>::SendGoal as WrappedServiceTypeSupport>::Response,
@ -317,7 +318,7 @@ where
}
}
fn handle_cancel_response(&mut self) -> () {
fn handle_cancel_response(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut response_msg = WrappedNativeMsg::<action_msgs::srv::CancelGoal::Response>::new();
@ -337,9 +338,8 @@ where
{
let (_, sender) = self.cancel_response_channels.swap_remove(idx);
let response = action_msgs::srv::CancelGoal::Response::from_native(&response_msg);
match sender.send(response) {
Err(e) => eprintln!("warning: could not send cancel response msg ({:?})", e),
_ => (),
if let Err(e) = sender.send(response) {
eprintln!("warning: could not send cancel response msg ({:?})", e)
}
} else {
let we_have: String = self
@ -356,7 +356,7 @@ where
}
}
fn handle_feedback_msg(&mut self) -> () {
fn handle_feedback_msg(&mut self) {
let mut feedback_msg = WrappedNativeMsg::<T::FeedbackMessage>::new();
let ret =
unsafe { rcl_action_take_feedback(&self.rcl_handle, feedback_msg.void_ptr_mut()) };
@ -369,15 +369,14 @@ where
.iter_mut()
.find(|(uuid, _)| uuid == &msg_uuid)
{
match sender.try_send(feedback) {
Err(e) => eprintln!("warning: could not send feedback msg ({})", e),
_ => (),
if let Err(e) = sender.try_send(feedback) {
eprintln!("warning: could not send feedback msg ({})", e)
}
}
}
}
fn handle_status_msg(&mut self) -> () {
fn handle_status_msg(&mut self) {
let mut status_array = WrappedNativeMsg::<action_msgs::msg::GoalStatusArray>::new();
let ret = unsafe { rcl_action_take_status(&self.rcl_handle, status_array.void_ptr_mut()) };
if ret == RCL_RET_OK as i32 {
@ -393,7 +392,7 @@ where
}
}
fn handle_result_response(&mut self) -> () {
fn handle_result_response(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut response_msg = WrappedNativeMsg::<
<<T as WrappedActionTypeSupport>::GetResult as WrappedServiceTypeSupport>::Response,
@ -446,7 +445,7 @@ where
}
}
fn send_result_request(&mut self, uuid: uuid::Uuid) -> () {
fn send_result_request(&mut self, uuid: uuid::Uuid) {
let uuid_msg = unique_identifier_msgs::msg::UUID {
uuid: uuid.as_bytes().to_vec(),
};

View File

@ -134,7 +134,7 @@ impl ActionClientUntyped {
.upgrade()
.ok_or(Error::RCL_RET_ACTION_CLIENT_INVALID)?;
let mut c = c.lock().unwrap();
c.send_result_request(uuid.clone());
c.send_result_request(uuid);
}
Ok((
@ -165,6 +165,10 @@ pub fn make_action_client_untyped(
ActionClientUntyped { client }
}
pub type ResultSender = (
uuid::Uuid,
oneshot::Sender<(GoalStatus, Result<serde_json::Value>)>,
);
pub struct WrappedActionClientUntyped {
pub action_type_support: UntypedActionSupport,
pub rcl_handle: rcl_action_client_t,
@ -173,10 +177,7 @@ pub struct WrappedActionClientUntyped {
Vec<(i64, oneshot::Sender<action_msgs::srv::CancelGoal::Response>)>,
pub feedback_senders: Vec<(uuid::Uuid, mpsc::Sender<Result<serde_json::Value>>)>,
pub result_requests: Vec<(i64, uuid::Uuid)>,
pub result_senders: Vec<(
uuid::Uuid,
oneshot::Sender<(GoalStatus, Result<serde_json::Value>)>,
)>,
pub result_senders: Vec<ResultSender>,
pub goal_status: HashMap<uuid::Uuid, GoalStatus>,
pub poll_available_channels: Vec<oneshot::Sender<()>>,
@ -237,7 +238,7 @@ impl ActionClient_ for WrappedActionClientUntyped {
&self.rcl_handle
}
fn handle_goal_response(&mut self) -> () {
fn handle_goal_response(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut response_msg = (self.action_type_support.make_goal_response_msg)();
@ -279,7 +280,7 @@ impl ActionClient_ for WrappedActionClientUntyped {
}
}
fn handle_cancel_response(&mut self) -> () {
fn handle_cancel_response(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut response_msg = WrappedNativeMsg::<action_msgs::srv::CancelGoal::Response>::new();
@ -299,9 +300,8 @@ impl ActionClient_ for WrappedActionClientUntyped {
{
let (_, sender) = self.cancel_response_channels.swap_remove(idx);
let response = action_msgs::srv::CancelGoal::Response::from_native(&response_msg);
match sender.send(response) {
Err(e) => eprintln!("warning: could not send cancel response msg ({:?})", e),
_ => (),
if let Err(e) = sender.send(response) {
eprintln!("warning: could not send cancel response msg ({:?})", e)
}
} else {
let we_have: String = self
@ -318,7 +318,7 @@ impl ActionClient_ for WrappedActionClientUntyped {
}
}
fn handle_feedback_msg(&mut self) -> () {
fn handle_feedback_msg(&mut self) {
let mut feedback_msg = (self.action_type_support.make_feedback_msg)();
let ret =
unsafe { rcl_action_take_feedback(&self.rcl_handle, feedback_msg.void_ptr_mut()) };
@ -331,15 +331,14 @@ impl ActionClient_ for WrappedActionClientUntyped {
.iter_mut()
.find(|(uuid, _)| uuid == &msg_uuid)
{
match sender.try_send(feedback) {
Err(e) => eprintln!("warning: could not send feedback msg ({})", e),
_ => (),
if let Err(e) = sender.try_send(feedback) {
eprintln!("warning: could not send feedback msg ({})", e)
}
}
}
}
fn handle_status_msg(&mut self) -> () {
fn handle_status_msg(&mut self) {
let mut status_array = WrappedNativeMsg::<action_msgs::msg::GoalStatusArray>::new();
let ret = unsafe { rcl_action_take_status(&self.rcl_handle, status_array.void_ptr_mut()) };
if ret == RCL_RET_OK as i32 {
@ -355,7 +354,7 @@ impl ActionClient_ for WrappedActionClientUntyped {
}
}
fn handle_result_response(&mut self) -> () {
fn handle_result_response(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut response_msg = (self.action_type_support.make_result_response_msg)();
let ret = unsafe {
@ -405,7 +404,7 @@ impl ActionClient_ for WrappedActionClientUntyped {
}
}
fn send_result_request(&mut self, uuid: uuid::Uuid) -> () {
fn send_result_request(&mut self, uuid: uuid::Uuid) {
let uuid_msg = unique_identifier_msgs::msg::UUID {
uuid: uuid.as_bytes().to_vec(),
};

View File

@ -18,25 +18,21 @@ use r2r_rcl::*;
pub trait ActionServer_ {
fn handle(&self) -> &rcl_action_server_t;
fn handle_mut(&mut self) -> &mut rcl_action_server_t;
fn handle_goal_request(&mut self, server: Arc<Mutex<dyn ActionServer_>>) -> ();
fn send_completed_cancel_requests(&mut self) -> ();
fn handle_cancel_request(&mut self) -> ();
fn handle_result_request(&mut self) -> ();
fn handle_goal_expired(&mut self) -> ();
fn publish_status(&self) -> ();
fn handle_goal_request(&mut self, server: Arc<Mutex<dyn ActionServer_>>);
fn send_completed_cancel_requests(&mut self);
fn handle_cancel_request(&mut self);
fn handle_result_request(&mut self);
fn handle_goal_expired(&mut self);
fn publish_status(&self);
fn set_goal_state(
&mut self,
uuid: &uuid::Uuid,
new_state: rcl_action_goal_event_t,
) -> Result<()>;
fn add_result(&mut self, uuid: uuid::Uuid, msg: Box<dyn VoidPtr>) -> ();
fn add_result(&mut self, uuid: uuid::Uuid, msg: Box<dyn VoidPtr>);
fn cancel_goal(&mut self, uuid: &uuid::Uuid);
fn is_cancelling(&self, uuid: &uuid::Uuid) -> Result<bool>;
fn add_goal_handle(
&mut self,
uuid: uuid::Uuid,
goal_handle: *mut rcl_action_goal_handle_t,
) -> ();
fn add_goal_handle(&mut self, uuid: uuid::Uuid, goal_handle: *mut rcl_action_goal_handle_t);
fn destroy(&mut self, node: &mut rcl_node_t);
}
@ -49,16 +45,14 @@ pub struct ActionServerCancelRequest {
impl ActionServerCancelRequest {
/// Accepts the cancel request. The action server should now cancel the corresponding goal.
pub fn accept(self) {
match self.response_sender.send((self.uuid, true)) {
Err(_) => eprintln!("warning: could not send goal canellation accept msg"),
_ => (),
if self.response_sender.send((self.uuid, true)).is_err() {
eprintln!("warning: could not send goal canellation accept msg")
}
}
/// Rejects the cancel request.
pub fn reject(self) {
match self.response_sender.send((self.uuid, false)) {
Err(_) => eprintln!("warning: could not send goal cancellation rejection"),
_ => (),
if self.response_sender.send((self.uuid, false)).is_err() {
eprintln!("warning: could not send goal cancellation rejection")
}
}
}
@ -129,15 +123,15 @@ where
server.publish_status();
let g = ActionServerGoal {
uuid: self.uuid.clone(),
uuid: self.uuid,
goal: self.goal,
server: self.server,
};
// server.goals.insert(g.uuid.clone(), goal_handle);
server.add_goal_handle(g.uuid.clone(), goal_handle);
server.add_goal_handle(g.uuid, goal_handle);
return Ok((g, self.cancel_requests));
Ok((g, self.cancel_requests))
}
/// reject the goal request and be consumed in the process
@ -165,6 +159,11 @@ where
Ok(())
}
}
pub type ActiveCancelRequest = (
rmw_request_id_t,
action_msgs::srv::CancelGoal::Response,
JoinAll<oneshot::Receiver<(uuid::Uuid, bool)>>,
);
pub struct WrappedActionServer<T>
where
@ -174,11 +173,7 @@ where
pub clock_handle: Box<rcl_clock_t>,
pub goal_request_sender: mpsc::Sender<ActionServerGoalRequest<T>>,
pub cancel_senders: HashMap<uuid::Uuid, mpsc::Sender<ActionServerCancelRequest>>,
pub active_cancel_requests: Vec<(
rmw_request_id_t,
action_msgs::srv::CancelGoal::Response,
JoinAll<oneshot::Receiver<(uuid::Uuid, bool)>>,
)>,
pub active_cancel_requests: Vec<ActiveCancelRequest>,
pub goals: HashMap<uuid::Uuid, *mut rcl_action_goal_handle_t>,
pub result_msgs: HashMap<uuid::Uuid, Box<dyn VoidPtr>>,
pub result_requests: HashMap<uuid::Uuid, Vec<rmw_request_id_t>>,
@ -266,7 +261,7 @@ where
Ok(())
} else {
return Err(Error::RCL_RET_ACTION_GOAL_HANDLE_INVALID);
Err(Error::RCL_RET_ACTION_GOAL_HANDLE_INVALID)
}
}
@ -284,7 +279,7 @@ where
Ok((uuid, do_cancel)) => {
// cancel goal and filter response msg.
if do_cancel {
canceled.push(uuid.clone());
canceled.push(uuid);
}
response_msg.goals_canceling.retain(|goal_info| {
@ -312,7 +307,7 @@ where
}
});
canceled.iter().for_each(|uuid| self.cancel_goal(&uuid));
canceled.iter().for_each(|uuid| self.cancel_goal(uuid));
if !canceled.is_empty() {
// at least one goal state changed, publish a new status message
self.publish_status();
@ -337,7 +332,7 @@ where
}
}
fn handle_goal_request(&mut self, server: Arc<Mutex<dyn ActionServer_>>) -> () {
fn handle_goal_request(&mut self, server: Arc<Mutex<dyn ActionServer_>>) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut request_msg = WrappedNativeMsg::<
<<T as WrappedActionTypeSupport>::SendGoal as WrappedServiceTypeSupport>::Request,
@ -359,7 +354,7 @@ where
let uuid = uuid_msg_to_uuid(&uuid_msg);
let (cancel_sender, cancel_receiver) = mpsc::channel::<ActionServerCancelRequest>(10);
self.cancel_senders.insert(uuid.clone(), cancel_sender);
self.cancel_senders.insert(uuid, cancel_sender);
let gr: ActionServerGoalRequest<T> = ActionServerGoalRequest {
uuid,
@ -370,13 +365,12 @@ where
};
// send out request.
match self.goal_request_sender.try_send(gr) {
Err(e) => eprintln!("warning: could not send service request ({})", e),
_ => (),
if let Err(e) = self.goal_request_sender.try_send(gr) {
eprintln!("warning: could not send service request ({})", e)
}
}
fn handle_cancel_request(&mut self) -> () {
fn handle_cancel_request(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut request_msg = WrappedNativeMsg::<action_msgs::srv::CancelGoal::Request>::new();
let ret = unsafe {
@ -417,7 +411,7 @@ where
.and_then(|cancel_sender| {
let (s, r) = oneshot::channel::<(uuid::Uuid, bool)>();
let cr = ActionServerCancelRequest {
uuid: uuid.clone(),
uuid,
response_sender: s,
};
match cancel_sender.try_send(cr) {
@ -485,16 +479,12 @@ where
}
}
fn add_goal_handle(
&mut self,
uuid: uuid::Uuid,
goal_handle: *mut rcl_action_goal_handle_t,
) -> () {
fn add_goal_handle(&mut self, uuid: uuid::Uuid, goal_handle: *mut rcl_action_goal_handle_t) {
self.goals.insert(uuid, goal_handle);
}
// bit of a hack...
fn add_result(&mut self, uuid: uuid::Uuid, mut msg: Box<dyn VoidPtr>) -> () {
fn add_result(&mut self, uuid: uuid::Uuid, mut msg: Box<dyn VoidPtr>) {
// if there are already requests for this goal, send the result immediately.
if let Some(rr) = self.result_requests.remove(&uuid) {
for mut req in rr {
@ -512,7 +502,7 @@ where
self.result_msgs.insert(uuid, msg);
}
fn handle_result_request(&mut self) -> () {
fn handle_result_request(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut request_msg = WrappedNativeMsg::<
<<T as WrappedActionTypeSupport>::GetResult as WrappedServiceTypeSupport>::Request,
@ -569,14 +559,13 @@ where
"action server: could send result request response. {}",
Error::from_rcl_error(ret)
);
return;
}
} else {
// keep request for later when result comes in
// todo: add logic that replies to the requests
self.result_requests
.entry(uuid)
.or_insert(vec![])
.or_insert_with(Vec::new)
.push(request_id);
}
}
@ -683,7 +672,7 @@ where
let native_msg = WrappedNativeMsg::<
<<T as WrappedActionTypeSupport>::GetResult as WrappedServiceTypeSupport>::Response,
>::from(&result_msg);
action_server.add_result(self.uuid.clone(), Box::new(native_msg));
action_server.add_result(self.uuid, Box::new(native_msg));
Ok(())
}
@ -703,7 +692,7 @@ where
let native_msg = WrappedNativeMsg::<
<<T as WrappedActionTypeSupport>::GetResult as WrappedServiceTypeSupport>::Response,
>::from(&result_msg);
action_server.add_result(self.uuid.clone(), Box::new(native_msg));
action_server.add_result(self.uuid, Box::new(native_msg));
Ok(())
}
@ -726,7 +715,7 @@ where
let native_msg = WrappedNativeMsg::<
<<T as WrappedActionTypeSupport>::GetResult as WrappedServiceTypeSupport>::Response,
>::from(&result_msg);
action_server.add_result(self.uuid.clone(), Box::new(native_msg));
action_server.add_result(self.uuid, Box::new(native_msg));
Ok(())
}

View File

@ -135,10 +135,10 @@ impl UntypedClient_ {
pub trait Client_ {
fn handle(&self) -> &rcl_client_t;
fn handle_response(&mut self) -> ();
fn register_poll_available(&mut self, s: oneshot::Sender<()>) -> ();
fn poll_available(&mut self, node: &mut rcl_node_t) -> ();
fn destroy(&mut self, node: &mut rcl_node_t) -> ();
fn handle_response(&mut self);
fn register_poll_available(&mut self, s: oneshot::Sender<()>);
fn poll_available(&mut self, node: &mut rcl_node_t);
fn destroy(&mut self, node: &mut rcl_node_t);
}
pub struct TypedClient<T>
@ -158,7 +158,7 @@ where
&self.rcl_handle
}
fn handle_response(&mut self) -> () {
fn handle_response(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut response_msg = WrappedNativeMsg::<T::Response>::new();
@ -244,7 +244,7 @@ impl Client_ for UntypedClient_ {
&self.rcl_handle
}
fn handle_response(&mut self) -> () {
fn handle_response(&mut self) {
let mut request_id = MaybeUninit::<rmw_request_id_t>::uninit();
let mut response_msg = (self.service_type.make_response_msg)();

View File

@ -76,13 +76,13 @@ pub struct ContextHandle(Box<rcl_context_t>);
impl Deref for ContextHandle {
type Target = Box<rcl_context_t>;
fn deref<'a>(&'a self) -> &'a Box<rcl_context_t> {
fn deref(&self) -> &Box<rcl_context_t> {
&self.0
}
}
impl DerefMut for ContextHandle {
fn deref_mut<'a>(&'a mut self) -> &'a mut Box<rcl_context_t> {
fn deref_mut(&mut self) -> &mut Box<rcl_context_t> {
&mut self.0
}
}

View File

@ -9,6 +9,7 @@ use std::fmt::Debug;
use std::ops::{Deref, DerefMut};
pub mod generated_msgs {
#![allow(clippy::all)]
use super::*;
include!(concat!(env!("OUT_DIR"), "/_r2r_generated_msgs.rs"));
include!(concat!(
@ -145,8 +146,8 @@ impl UntypedServiceSupport {
where
T: WrappedServiceTypeSupport,
{
let make_request_msg = || WrappedNativeMsgUntyped::new::<T::Request>();
let make_response_msg = || WrappedNativeMsgUntyped::new::<T::Response>();
let make_request_msg = WrappedNativeMsgUntyped::new::<T::Request>;
let make_response_msg = WrappedNativeMsgUntyped::new::<T::Response>;
UntypedServiceSupport {
ts: T::get_ts(),
@ -185,7 +186,7 @@ pub struct UntypedActionSupport {
impl UntypedActionSupport {
fn new<T>() -> Self
where
T: WrappedActionTypeSupport,
T: WrappedActionTypeSupport + 'static,
{
// TODO: this is terrible. These closures perform json (de)serialization just to move the data.
// FIX.
@ -194,8 +195,7 @@ impl UntypedActionSupport {
let goal_msg: T::Goal =
serde_json::from_value(goal).expect("TODO: move this error handling");
let request_msg = T::make_goal_request_msg(goal_id, goal_msg);
let json =
serde_json::to_value(request_msg.clone()).expect("TODO: move this error handling");
let json = serde_json::to_value(request_msg).expect("TODO: move this error handling");
let mut native_untyped = WrappedNativeMsgUntyped::new::<
<<T as WrappedActionTypeSupport>::SendGoal as WrappedServiceTypeSupport>::Request,
>();
@ -220,7 +220,7 @@ impl UntypedActionSupport {
T::destructure_goal_response_msg(msg)
});
let make_feedback_msg = Box::new(|| WrappedNativeMsgUntyped::new::<T::FeedbackMessage>());
let make_feedback_msg = Box::new(WrappedNativeMsgUntyped::new::<T::FeedbackMessage>);
let destructure_feedback_msg = Box::new(|msg: WrappedNativeMsgUntyped| {
let msg = unsafe {
@ -237,8 +237,7 @@ impl UntypedActionSupport {
let make_result_request_msg = Box::new(|uuid_msg: unique_identifier_msgs::msg::UUID| {
let request_msg = T::make_result_request_msg(uuid_msg);
let json =
serde_json::to_value(request_msg.clone()).expect("TODO: move this error handling");
let json = serde_json::to_value(request_msg).expect("TODO: move this error handling");
let mut native_untyped = WrappedNativeMsgUntyped::new::<
<<T as WrappedActionTypeSupport>::GetResult as WrappedServiceTypeSupport>::Request,
@ -363,6 +362,15 @@ where
}
}
impl<T> Default for WrappedNativeMsg<T>
where
T: WrappedTypesupport,
{
fn default() -> Self {
Self::new()
}
}
impl<T: 'static> VoidPtr for WrappedNativeMsg<T>
where
T: WrappedTypesupport,
@ -412,7 +420,7 @@ mod tests {
use r2r_rcl::*;
#[test]
fn test_ros_str() -> () {
fn test_ros_str() {
let hej = "hej hopp";
let mut msg = WrappedNativeMsg::<std_msgs::msg::String>::new();
msg.data.assign(hej);
@ -420,7 +428,7 @@ mod tests {
}
#[test]
fn test_copy_fields() -> () {
fn test_copy_fields() {
let msg_orig = std_msgs::msg::String { data: "hej".into() };
let rosmsg = WrappedNativeMsg::<std_msgs::msg::String>::from(&msg_orig);
let msg2 = std_msgs::msg::String::from_native(&rosmsg);
@ -428,7 +436,7 @@ mod tests {
}
#[test]
fn test_introspection_string() -> () {
fn test_introspection_string() {
unsafe {
use std::ffi::CStr;
@ -456,13 +464,13 @@ mod tests {
type_id,
rosidl_typesupport_introspection_c__ROS_TYPE_STRING as u8
);
assert_eq!(is_array, false);
assert!(!is_array);
}
}
#[test]
#[should_panic] // we are testing that we cannot have to many elements in a fixed sized field
fn test_fixedsizearray() -> () {
fn test_fixedsizearray() {
unsafe {
let x = rosidl_typesupport_introspection_c__get_message_type_support_handle__geometry_msgs__msg__AccelWithCovariance();
let members = (*x).data as *const rosidl_typesupport_introspection_c__MessageMembers;
@ -490,7 +498,7 @@ mod tests {
#[test]
#[should_panic] // we are testing that we cannot have to many elements in a fixed sized field
fn test_capped_sequence() -> () {
fn test_capped_sequence() {
// float64[<=3] dimensions in the .msg translates to a float64 sequence AND an array size field. handle it...
unsafe {
let x = rosidl_typesupport_introspection_c__get_message_type_support_handle__shape_msgs__msg__SolidPrimitive();
@ -515,7 +523,7 @@ mod tests {
}
#[test]
fn test_generation_string_use() -> () {
fn test_generation_string_use() {
let msg = std_msgs::msg::String { data: "hej".into() };
let msg2 = msg.clone();
let msg_native = WrappedNativeMsg::<std_msgs::msg::String>::from(&msg2);
@ -524,7 +532,7 @@ mod tests {
}
#[test]
fn test_generation_bool_use() -> () {
fn test_generation_bool_use() {
let msg = std_msgs::msg::Bool { data: true };
let msg_native = WrappedNativeMsg::<std_msgs::msg::Bool>::from(&msg);
let msg2 = std_msgs::msg::Bool::from_native(&msg_native);
@ -532,7 +540,7 @@ mod tests {
}
#[test]
fn test_float_sequence() -> () {
fn test_float_sequence() {
use trajectory_msgs::msg::*;
let native = WrappedNativeMsg::<JointTrajectoryPoint>::new();
let mut msg = JointTrajectoryPoint::from_native(&native);
@ -545,7 +553,7 @@ mod tests {
}
#[test]
fn test_deault() -> () {
fn test_deault() {
use trajectory_msgs::msg::*;
let mut msg: JointTrajectoryPoint = Default::default();
msg.positions.push(39.0);
@ -558,7 +566,7 @@ mod tests {
}
#[test]
fn test_untyped_json() -> () {
fn test_untyped_json() {
let mut msg = trajectory_msgs::msg::JointTrajectoryPoint::default();
msg.positions.push(39.0);
msg.positions.push(34.0);

View File

@ -60,7 +60,7 @@ impl Node {
/// Returns the name of the node.
pub fn name(&self) -> Result<String> {
let cstr = unsafe { rcl_node_get_name(self.node_handle.as_ref()) };
if cstr == std::ptr::null() {
if cstr.is_null() {
return Err(Error::RCL_RET_NODE_INVALID);
}
let s = unsafe { CStr::from_ptr(cstr) };
@ -70,7 +70,7 @@ impl Node {
/// Returns the fully qualified name of the node.
pub fn fully_qualified_name(&self) -> Result<String> {
let cstr = unsafe { rcl_node_get_fully_qualified_name(self.node_handle.as_ref()) };
if cstr == std::ptr::null() {
if cstr.is_null() {
return Err(Error::RCL_RET_NODE_INVALID);
}
let s = unsafe { CStr::from_ptr(cstr) };
@ -80,7 +80,7 @@ impl Node {
/// Returns the namespace of the node.
pub fn namespace(&self) -> Result<String> {
let cstr = unsafe { rcl_node_get_namespace(self.node_handle.as_ref()) };
if cstr == std::ptr::null() {
if cstr.is_null() {
return Err(Error::RCL_RET_NODE_INVALID);
}
let s = unsafe { CStr::from_ptr(cstr) };
@ -98,7 +98,7 @@ impl Node {
return Err(Error::from_rcl_error(ret));
}
if *params == std::ptr::null_mut() {
if params.is_null() {
return Ok(());
}
@ -231,7 +231,7 @@ impl Node {
.lock()
.unwrap()
.get(&p.name)
.and_then(|v| Some(v != &val))
.map(|v| v != &val)
.unwrap_or(true); // changed=true if new
params.lock().unwrap().insert(p.name.clone(), val.clone());
let r = rcl_interfaces::msg::SetParametersResult {
@ -241,12 +241,9 @@ impl Node {
result.results.push(r);
// if the value changed, send out new value on parameter event stream
if changed {
match event_tx.try_send((p.name.clone(), val)) {
Err(e) => {
if let Err(e) = event_tx.try_send((p.name.clone(), val)) {
println!("Warning: could not send parameter event ({}).", e);
}
_ => {} // ok
}
}
}
req.respond(result)
@ -275,7 +272,7 @@ impl Node {
Some(v) => v.clone(),
None => ParameterValue::NotSet,
})
.map(|v| v.clone().to_parameter_value_msg())
.map(|v| v.into_parameter_value_msg())
.collect::<Vec<rcl_interfaces::msg::ParameterValue>>();
let result = rcl_interfaces::srv::GetParameters::Response { values };
@ -993,9 +990,9 @@ impl Node {
}
/// Get the ros logger name for this node.
pub fn logger<'a>(&'a self) -> &'a str {
pub fn logger(&self) -> &str {
let ptr = unsafe { rcl_node_get_logger_name(self.node_handle.as_ref()) };
if ptr == std::ptr::null() {
if ptr.is_null() {
return "";
}
let s = unsafe { CStr::from_ptr(ptr) };
@ -1013,32 +1010,28 @@ impl Timer_ {
fn handle_incoming(&mut self) -> bool {
let mut is_ready = false;
let ret = unsafe { rcl_timer_is_ready(&self.timer_handle, &mut is_ready) };
if ret == RCL_RET_OK as i32 {
if is_ready {
if ret == RCL_RET_OK as i32 && is_ready {
let mut nanos = 0i64;
// todo: error handling
let ret =
unsafe { rcl_timer_get_time_since_last_call(&self.timer_handle, &mut nanos) };
let ret = unsafe { rcl_timer_get_time_since_last_call(&self.timer_handle, &mut nanos) };
if ret == RCL_RET_OK as i32 {
let ret = unsafe { rcl_timer_call(&mut self.timer_handle) };
if ret == RCL_RET_OK as i32 {
match self.sender.try_send(Duration::from_nanos(nanos as u64)) {
Err(e) => {
if let Err(e) = self.sender.try_send(Duration::from_nanos(nanos as u64)) {
if e.is_disconnected() {
// client dropped the timer handle, let's drop our timer as well.
return true;
}
if e.is_full() {
println!("Warning: timer tick not handled in time - no wakeup will occur");
}
}
_ => {} // ok
println!(
"Warning: timer tick not handled in time - no wakeup will occur"
);
}
}
}
}
}
return false;
false
}
}

View File

@ -20,43 +20,43 @@ pub enum ParameterValue {
impl ParameterValue {
pub(crate) fn from_rcl(v: &rcl_variant_t) -> Self {
if v.bool_value != std::ptr::null_mut() {
if !v.bool_value.is_null() {
ParameterValue::Bool(unsafe { *v.bool_value })
} else if v.integer_value != std::ptr::null_mut() {
} else if !v.integer_value.is_null() {
ParameterValue::Integer(unsafe { *v.integer_value })
} else if v.double_value != std::ptr::null_mut() {
} else if !v.double_value.is_null() {
ParameterValue::Double(unsafe { *v.double_value })
} else if v.string_value != std::ptr::null_mut() {
} else if !v.string_value.is_null() {
let s = unsafe { CStr::from_ptr(v.string_value) };
let string = s.to_str().unwrap_or("").to_owned();
ParameterValue::String(string)
} else if v.byte_array_value != std::ptr::null_mut() {
} else if !v.byte_array_value.is_null() {
let vals = unsafe {
std::slice::from_raw_parts((*v.byte_array_value).values, (*v.byte_array_value).size)
};
ParameterValue::ByteArray(vals.iter().cloned().collect())
} else if v.bool_array_value != std::ptr::null_mut() {
ParameterValue::ByteArray(vals.to_vec())
} else if !v.bool_array_value.is_null() {
let vals = unsafe {
std::slice::from_raw_parts((*v.bool_array_value).values, (*v.bool_array_value).size)
};
ParameterValue::BoolArray(vals.iter().cloned().collect())
} else if v.integer_array_value != std::ptr::null_mut() {
ParameterValue::BoolArray(vals.to_vec())
} else if !v.integer_array_value.is_null() {
let vals = unsafe {
std::slice::from_raw_parts(
(*v.integer_array_value).values,
(*v.integer_array_value).size,
)
};
ParameterValue::IntegerArray(vals.iter().cloned().collect())
} else if v.double_array_value != std::ptr::null_mut() {
ParameterValue::IntegerArray(vals.to_vec())
} else if !v.double_array_value.is_null() {
let vals = unsafe {
std::slice::from_raw_parts(
(*v.double_array_value).values,
(*v.double_array_value).size,
)
};
ParameterValue::DoubleArray(vals.iter().cloned().collect())
} else if v.string_array_value != std::ptr::null_mut() {
ParameterValue::DoubleArray(vals.to_vec())
} else if !v.string_array_value.is_null() {
let vals = unsafe {
std::slice::from_raw_parts(
(*v.string_array_value).data,
@ -96,7 +96,7 @@ impl ParameterValue {
}
}
pub(crate) fn to_parameter_value_msg(self) -> rcl_interfaces::msg::ParameterValue {
pub(crate) fn into_parameter_value_msg(self) -> rcl_interfaces::msg::ParameterValue {
let mut ret = rcl_interfaces::msg::ParameterValue::default();
match self {

View File

@ -47,7 +47,7 @@ pub trait Service_ {
fn send_response(&mut self, request_id: rmw_request_id_t, msg: Box<dyn VoidPtr>) -> Result<()>;
/// Returns true if the service stream has been dropped.
fn handle_request(&mut self, service: Arc<Mutex<dyn Service_>>) -> bool;
fn destroy(&mut self, node: &mut rcl_node_t) -> ();
fn destroy(&mut self, node: &mut rcl_node_t);
}
pub struct TypedService<T>
@ -100,17 +100,14 @@ where
request_id,
service: Arc::downgrade(&service),
};
match self.sender.try_send(request) {
Err(e) => {
if let Err(e) = self.sender.try_send(request) {
if e.is_disconnected() {
return true;
}
eprintln!("warning: could not send service request ({})", e)
}
_ => (),
}
} // TODO handle failure.
return false;
false
}
fn destroy(&mut self, node: &mut rcl_node_t) {

View File

@ -10,7 +10,7 @@ pub trait Subscriber_ {
fn handle(&self) -> &rcl_subscription_t;
/// Returns true if the subscriber stream has been dropped.
fn handle_incoming(&mut self) -> bool;
fn destroy(&mut self, node: &mut rcl_node_t) -> ();
fn destroy(&mut self, node: &mut rcl_node_t);
}
pub struct TypedSubscriber<T>
@ -56,18 +56,15 @@ where
};
if ret == RCL_RET_OK as i32 {
let msg = T::from_native(&msg);
match self.sender.try_send(msg) {
Err(e) => {
if let Err(e) = self.sender.try_send(msg) {
if e.is_disconnected() {
// user dropped the handle to the stream, signal removal.
return true;
}
println!("error {:?}", e)
}
_ => (),
}
}
return false;
false
}
fn destroy(&mut self, node: &mut rcl_node_t) {
@ -97,18 +94,15 @@ where
)
};
if ret == RCL_RET_OK as i32 {
match self.sender.try_send(msg) {
Err(e) => {
if let Err(e) = self.sender.try_send(msg) {
if e.is_disconnected() {
// user dropped the handle to the stream, signal removal.
return true;
}
println!("error {:?}", e)
}
_ => (),
}
}
return false;
false
}
fn destroy(&mut self, node: &mut rcl_node_t) {
@ -126,7 +120,7 @@ impl Subscriber_ for UntypedSubscriber {
fn handle_incoming(&mut self) -> bool {
let mut msg_info = rmw_message_info_t::default(); // we dont care for now
let mut msg = WrappedNativeMsgUntyped::new_from(&self.topic_type)
.expect(&format!("no typesupport for {}", self.topic_type));
.unwrap_or_else(|_| panic!("no typesupport for {}", self.topic_type));
let ret = unsafe {
rcl_take(
&self.rcl_handle,
@ -137,18 +131,15 @@ impl Subscriber_ for UntypedSubscriber {
};
if ret == RCL_RET_OK as i32 {
let json = msg.to_json();
match self.sender.try_send(json) {
Err(e) => {
if let Err(e) = self.sender.try_send(json) {
if e.is_disconnected() {
// user dropped the handle to the stream, signal removal.
return true;
}
println!("error {:?}", e)
}
_ => (),
}
}
return false;
false
}
fn destroy(&mut self, node: &mut rcl_node_t) {