Able to generate convenience types for all built in dashing messages

This commit is contained in:
Martin Dahl 2019-08-20 17:21:39 +02:00
parent f427e06b02
commit 7f5605c6ab
6 changed files with 207 additions and 84 deletions

View File

@ -33,7 +33,7 @@ fn main() -> Result<(), ()> {
};
let cb3 = move |raw_c:&WrappedNativeMsg<JointTrajectoryPoint>| {
println!("Raw c data: {:?}", (*raw_c).positions);
println!("Raw c data: {:?}", raw_c.positions);
};
let sub1 = rcl_create_subscription(&mut node, "/hopp", Box::new(cb))?;

View File

@ -60,7 +60,23 @@ fn main() {
.blacklist_type("rosidl_message_type_support_t")
.blacklist_type("rosidl_generator_c__String")
.blacklist_type("rosidl_generator_c__String__Sequence")
.blacklist_type("rosidl_generator_c__double__Sequence") // etc...
.blacklist_type("rosidl_generator_c__float32__Sequence")
.blacklist_type("rosidl_generator_c__float__Sequence")
.blacklist_type("rosidl_generator_c__float64__Sequence")
.blacklist_type("rosidl_generator_c__double__Sequence")
.blacklist_type("rosidl_generator_c__long_double__Sequence")
.blacklist_type("rosidl_generator_c__char__Sequence")
.blacklist_type("rosidl_generator_c__wchar__Sequence")
.blacklist_type("rosidl_generator_c__boolean__Sequence")
.blacklist_type("rosidl_generator_c__octet__Sequence")
.blacklist_type("rosidl_generator_c__uint8__Sequence")
.blacklist_type("rosidl_generator_c__int8__Sequence")
.blacklist_type("rosidl_generator_c__uint16__Sequence")
.blacklist_type("rosidl_generator_c__int16__Sequence")
.blacklist_type("rosidl_generator_c__uint32__Sequence")
.blacklist_type("rosidl_generator_c__int32__Sequence")
.blacklist_type("rosidl_generator_c__uint64__Sequence")
.blacklist_type("rosidl_generator_c__int64__Sequence")
.default_enum_style(bindgen::EnumVariation::Rust { non_exhaustive: false } );
let ament_prefix_var_name = "AMENT_PREFIX_PATH";

View File

@ -15,33 +15,24 @@ use rcl::*;
use std::ffi::CStr;
fn field_type(t: u8) -> String {
// rosidl_typesupport_introspection_c__ROS_TYPE_FLOAT = 1,
// rosidl_typesupport_introspection_c__ROS_TYPE_DOUBLE = 2,
// rosidl_typesupport_introspection_c__ROS_TYPE_LONG_DOUBLE = 3,
// rosidl_typesupport_introspection_c__ROS_TYPE_CHAR = 4,
// rosidl_typesupport_introspection_c__ROS_TYPE_WCHAR = 5,
// rosidl_typesupport_introspection_c__ROS_TYPE_BOOLEAN = 6,
// rosidl_typesupport_introspection_c__ROS_TYPE_OCTET = 7,
// rosidl_typesupport_introspection_c__ROS_TYPE_UINT8 = 8,
// rosidl_typesupport_introspection_c__ROS_TYPE_INT8 = 9,
// rosidl_typesupport_introspection_c__ROS_TYPE_UINT16 = 10,
// rosidl_typesupport_introspection_c__ROS_TYPE_INT16 = 11,
// rosidl_typesupport_introspection_c__ROS_TYPE_UINT32 = 12,
// rosidl_typesupport_introspection_c__ROS_TYPE_INT32 = 13,
// rosidl_typesupport_introspection_c__ROS_TYPE_UINT64 = 14,
// rosidl_typesupport_introspection_c__ROS_TYPE_INT64 = 15,
// rosidl_typesupport_introspection_c__ROS_TYPE_STRING = 16,
// rosidl_typesupport_introspection_c__ROS_TYPE_WSTRING = 17,
// rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE = 18,
// todo: add these as needed...
// lovely...
// move to common
if t == (rosidl_typesupport_introspection_c__ROS_TYPE_STRING as u8) { "std::string::String".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_BOOLEAN as u8) { "bool".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_CHAR as u8) { "i8".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_WCHAR as u8) { "u16".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_OCTET as u8) { "u8".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_UINT8 as u8) { "u8".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_INT8 as u8) { "i8".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_UINT16 as u8) { "u16".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_INT16 as u8) { "i16".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_UINT32 as u8) { "u32".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_INT32 as u8) { "i32".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_UINT64 as u8) { "u64".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_INT64 as u8) { "i64".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_FLOAT as u8) { "f32".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_DOUBLE as u8) { "f64".to_owned() }
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_LONG_DOUBLE as u8) { "u128".to_owned() } // f128 does not exist in rust
else if t == (rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE as u8) { "message".to_owned() }
else { panic!("ros native type not implemented: {}", t); }
@ -67,8 +58,10 @@ pub fn generate_rust_msg(module: &str, prefix: &str, name: &str) -> String {
for member in memberslice {
let field_name = CStr::from_ptr((*member).name_).to_str().unwrap();
let field_name = if field_name == "type" { "type_" } else { field_name };
let type_id = (*member).type_id_;
let is_array = (*member).is_array_; // TODO: use
let is_array = (*member).is_array_;
let _array_size = (*member).array_size_;
let rust_field_type = field_type(type_id);
let rust_field_type = if rust_field_type == "message" {
// perform a hack!
@ -81,27 +74,58 @@ pub fn generate_rust_msg(module: &str, prefix: &str, name: &str) -> String {
format!("{module}::{prefix}::{msgname}", module = module, prefix=prefix, msgname = name)
} else { rust_field_type };
let s = if is_array {
// if array_size > 0 {
// fixed size array
// format!("pub {}: [{};{}usize],\n",field_name, rust_field_type, array_size)
// actually lets use a vector anyway because its more convenient with traits. assert on the fixed size instead!
//} else {
// vector type
format!("pub {}: Vec<{}>,\n",field_name, rust_field_type)
//}
} else {
format!("pub {}: {},\n",field_name, rust_field_type)
};
fields.push_str(&s);
}
let mut from_native = String::new();
from_native.push_str(&format!("fn from_native(msg: &Self::CStruct) -> {} {{\n", name));
from_native.push_str(&format!(" {} {{\n", name));
for member in memberslice {
let field_name = CStr::from_ptr((*member).name_).to_str().unwrap();
let field_name = if field_name == "type" { "type_" } else { field_name };
let type_id = (*member).type_id_;
let is_array = (*member).is_array_; // TODO: use
let is_array = (*member).is_array_;
let array_size = (*member).array_size_;
let rust_field_type = field_type(type_id);
if is_array {
from_native.push_str(&format!("{field_name}: msg.{field_name}.to_vec(),\n", field_name = field_name));
if rust_field_type == "message" {
// perform a hack!
let ts = (*member).members_;
let members = (*ts).data as *const rosidl_typesupport_introspection_c__MessageMembers;
let namespace = CStr::from_ptr((*members).message_namespace_).to_str().unwrap();
let name = CStr::from_ptr((*members).message_name_).to_str().unwrap();
let nn: Vec<&str> = namespace.split("__").into_iter().take(2).collect();
let (module, prefix) = ( nn[0], nn[1] );
from_native.push_str(&format!("{field_name} : {{\n", field_name = field_name));
from_native.push_str(&format!("let mut temp = Vec::with_capacity(msg.{field_name}.size);\n",field_name = field_name));
from_native.push_str(&format!("let slice = unsafe {{ std::slice::from_raw_parts(msg.{field_name}.data, msg.{field_name}.size)}};\n",field_name = field_name));
from_native.push_str(&format!("for s in slice {{ temp.push({module}::{prefix}::{msgname}::from_native(s)); }}\n", module = module, prefix=prefix, msgname = name));
from_native.push_str("temp },\n");
} else {
if array_size > 0 {
// fixed size array, copy elements (happens to be the same now that we are using vectors...)
from_native.push_str(&format!("{field_name}: msg.{field_name}.to_vec(),\n", field_name = field_name));
} else {
from_native.push_str(&format!("{field_name}: msg.{field_name}.to_vec(),\n", field_name = field_name));
}
}
} else if rust_field_type == "std::string::String" {
from_native.push_str(&format!("{field_name}: msg.{field_name}.to_str().to_owned(),\n", field_name = field_name));
} else if rust_field_type == "message" {
@ -112,7 +136,7 @@ pub fn generate_rust_msg(module: &str, prefix: &str, name: &str) -> String {
let name = CStr::from_ptr((*members).message_name_).to_str().unwrap();
let nn: Vec<&str> = namespace.split("__").into_iter().take(2).collect();
let (module, prefix) = ( nn[0], nn[1] );
from_native.push_str(&format!("{field_name}: {module}::{prefix}::{msgname}::from_native(&msg.{field_name}),", field_name = field_name, module = module, prefix=prefix, msgname = name));
from_native.push_str(&format!("{field_name}: {module}::{prefix}::{msgname}::from_native(&msg.{field_name}),\n", field_name = field_name, module = module, prefix=prefix, msgname = name));
} else {
from_native.push_str(&format!("{field_name}: msg.{field_name},\n", field_name = field_name));
}
@ -124,18 +148,47 @@ pub fn generate_rust_msg(module: &str, prefix: &str, name: &str) -> String {
for member in memberslice {
let field_name = CStr::from_ptr((*member).name_).to_str().unwrap();
let field_name = if field_name == "type" { "type_" } else { field_name };
let type_id = (*member).type_id_;
let is_array = (*member).is_array_; // TODO: use
let is_array = (*member).is_array_;
let array_size = (*member).array_size_;
let is_upper_bound = (*member).is_upper_bound_; // not fixed size just bounded sequence
let rust_field_type = field_type(type_id);
// handle other special cases...
if is_array {
copy_to_native.push_str(&format!("msg.{field_name}.update(&self.{field_name});\n", field_name = field_name));
if rust_field_type == "message" {
// perform a hack!
let ts = (*member).members_;
let members = (*ts).data as *const rosidl_typesupport_introspection_c__MessageMembers;
let namespace = CStr::from_ptr((*members).message_namespace_).to_str().unwrap();
let name = CStr::from_ptr((*members).message_name_).to_str().unwrap();
let nn: Vec<&str> = namespace.split("__").into_iter().take(2).collect();
let (module, prefix) = ( nn[0], nn[1] );
let c_struct = format!("{module}__{prefix}__{msgname}", module = module, prefix=prefix, msgname = name);
copy_to_native.push_str(&format!("unsafe {{ {c_struct}__Sequence__fini(&mut msg.{field_name}) }};\n", c_struct = c_struct, field_name = field_name));
copy_to_native.push_str(&format!("unsafe {{ {c_struct}__Sequence__init(&mut msg.{field_name}, self.{field_name}.len()) }};\n", c_struct = c_struct, field_name = field_name));
copy_to_native.push_str(&format!("let slice = unsafe {{ std::slice::from_raw_parts_mut(msg.{field_name}.data, msg.{field_name}.size)}};\n",field_name = field_name));
copy_to_native.push_str(&format!("for (t,s) in slice.iter_mut().zip(&self.{field_name}) {{ s.copy_to_native(t);}}\n", field_name=field_name));
} else {
if array_size > 0 && !is_upper_bound {
// fixed size array, just copy but first check the size!
copy_to_native.push_str(&format!("assert_eq!(self.{field_name}.len(), {array_size}, \"Field {{}} is fixed size of {{}}!\", \"{field_name}\", {array_size});\n", field_name = field_name, array_size = array_size));
copy_to_native.push_str(&format!("msg.{field_name}.copy_from_slice(&self.{field_name}[..{array_size}]);\n", field_name = field_name, array_size = array_size));
} else {
if is_upper_bound {
// extra assertion
copy_to_native.push_str(&format!("assert!(self.{field_name}.len() <= {array_size}, \"Field {{}} is upper bounded by {{}}!\", \"{field_name}\", {array_size});\n", field_name = field_name, array_size = array_size));
}
copy_to_native.push_str(&format!("msg.{field_name}.update(&self.{field_name});\n", field_name = field_name));
}
}
} else if rust_field_type == "std::string::String" {
copy_to_native.push_str(&format!("msg.{field_name}.assign(&self.{field_name});\n", field_name = field_name));
} else if rust_field_type == "message" {
copy_to_native.push_str(&format!("self.{field_name}.copy_to_native(&mut msg.{field_name});", field_name = field_name));
copy_to_native.push_str(&format!("self.{field_name}.copy_to_native(&mut msg.{field_name});\n", field_name = field_name));
} else {
copy_to_native.push_str(&format!("msg.{field_name} = self.{field_name};\n", field_name = field_name));
}
@ -180,4 +233,3 @@ mod tests {
assert_eq!(generate_rust_msg("std_msgs", "msg", "string"), "hej");
}
}

View File

@ -9,6 +9,7 @@ headers = []
[dependencies]
libc = "0.2.0"
paste = "0.1.6"
[build-dependencies]
bindgen = "0.50.0"

View File

@ -9,24 +9,6 @@ pub use rcl_bindings::*;
use std::ffi::CStr;
use std::ffi::CString;
// special treatment to convert to/from rust strings.
// ros strings are owned by ros, assignment is a copy
impl rosidl_generator_c__String {
pub fn to_str(&self) -> &str {
let s = unsafe { CStr::from_ptr(self.data as *mut i8) };
s.to_str().unwrap_or("")
}
pub fn assign(&mut self, other: &str) -> () {
let q = CString::new(other).unwrap();
let to_send_ptr = q.as_ptr() as *const i8;
unsafe {
rosidl_generator_c__String__assign(self as *mut _, to_send_ptr);
}
}
}
impl Default for rmw_message_info_t {
fn default() -> Self {
rmw_message_info_t {
@ -56,8 +38,22 @@ impl Default for rmw_qos_profile_t {
}
// conversions from/to vectors
// macro:ify this increase maintainability
// special treatment to convert to/from rust strings.
// ros strings are owned by ros, assignment is a copy
impl rosidl_generator_c__String {
pub fn to_str(&self) -> &str {
let s = unsafe { CStr::from_ptr(self.data as *mut i8) };
s.to_str().unwrap_or("")
}
pub fn assign(&mut self, other: &str) -> () {
let q = CString::new(other).unwrap();
let to_send_ptr = q.as_ptr() as *const i8;
unsafe {
rosidl_generator_c__String__assign(self as *mut _, to_send_ptr);
}
}
}
impl rosidl_generator_c__String__Sequence {
pub fn update(&mut self, values: &[String]) {
@ -70,45 +66,52 @@ impl rosidl_generator_c__String__Sequence {
}
pub fn to_vec(&self) -> Vec<String> {
let mut dst = Vec::with_capacity(self.size);
let mut target = Vec::with_capacity(self.size);
let strs = unsafe { std::slice::from_raw_parts(self.data, self.size) };
for s in strs {
dst.push(s.to_str().to_owned());
target.push(s.to_str().to_owned());
}
dst
target
}
// dont think we need fini? surely messages call fini on all their fields...?
//
// extern "C" {
// pub fn rosidl_generator_c__float64__Sequence__fini(
// sequence: *mut rosidl_generator_c__double__Sequence,
// );
// }
}
// conversions from/to vectors of built in types
impl rosidl_generator_c__double__Sequence {
pub fn update(&mut self, values: &[f64]) {
// crash here?
unsafe { rosidl_generator_c__float64__Sequence__fini(self as *mut _); }
unsafe { rosidl_generator_c__float64__Sequence__init(self as *mut _, values.len()); }
unsafe { std::ptr::copy(values.as_ptr(), self.data, values.len()); }
macro_rules! primitive_sequence {
($ctype:ident, $element_type:ident) => {
paste::item! {
impl [<$ctype __Sequence>] {
pub fn update(&mut self, values: &[$element_type]) {
unsafe { [<$ctype __Sequence__fini>] (self as *mut _); }
unsafe { [<$ctype __Sequence__init>] (self as *mut _, values.len()); }
unsafe { std::ptr::copy(values.as_ptr(), self.data, values.len()); }
}
pub fn to_vec(&self) -> Vec<$element_type> {
let mut target = Vec::with_capacity(self.size);
unsafe { target.set_len(self.size); }
unsafe { std::ptr::copy(self.data, target.as_mut_ptr(), self.size); }
target
}
}
}
}
pub fn to_vec(&self) -> Vec<f64> {
let mut dst = Vec::with_capacity(self.size);
unsafe { dst.set_len(self.size); }
unsafe { std::ptr::copy(self.data, dst.as_mut_ptr(), self.size); }
dst
}
// dont think we need fini? surely messages call fini on all their fields...?
//
// extern "C" {
// pub fn rosidl_generator_c__float64__Sequence__fini(
// sequence: *mut rosidl_generator_c__double__Sequence,
// );
// }
}
primitive_sequence!(rosidl_generator_c__float32, f32);
primitive_sequence!(rosidl_generator_c__float64, f64);
primitive_sequence!(rosidl_generator_c__long_double, u128);
primitive_sequence!(rosidl_generator_c__char, i8);
primitive_sequence!(rosidl_generator_c__wchar, u16);
primitive_sequence!(rosidl_generator_c__boolean, bool);
primitive_sequence!(rosidl_generator_c__octet, u8);
primitive_sequence!(rosidl_generator_c__uint8, u8);
primitive_sequence!(rosidl_generator_c__int8, i8);
primitive_sequence!(rosidl_generator_c__uint16, u16);
primitive_sequence!(rosidl_generator_c__int16, i16);
primitive_sequence!(rosidl_generator_c__uint32, u32);
primitive_sequence!(rosidl_generator_c__int32, i32);
primitive_sequence!(rosidl_generator_c__uint64, u64);
primitive_sequence!(rosidl_generator_c__int64, i64);

View File

@ -428,6 +428,57 @@ mod tests {
}
}
#[test]
#[should_panic] // we are testing that we cannot have to many elements in a fixed sized field
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;
println!("{:#?}", *members);
let memberslice = std::slice::from_raw_parts((*members).members_, (*members).member_count_ as usize);
for member in memberslice {
println!("member: {:#?}", *member);
}
let msg_native = WrappedNativeMsg::<geometry_msgs::msg::AccelWithCovariance>::new();
let mut msg = geometry_msgs::msg::AccelWithCovariance::from_native(&msg_native);
println!("{:#?}", msg);
msg.covariance[0] = 10.0;
msg.covariance[10] = 10.0;
msg.covariance[35] = 99.0;
msg.covariance.push(4444.0);
let msg_native2 = WrappedNativeMsg::<geometry_msgs::msg::AccelWithCovariance>::from(&msg);
let msg2 = geometry_msgs::msg::AccelWithCovariance::from_native(&msg_native2);
println!("{:#?}", msg2);
}
}
#[test]
#[should_panic] // we are testing that we cannot have to many elements in a fixed sized field
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();
let members = (*x).data as *const rosidl_typesupport_introspection_c__MessageMembers;
println!("{:#?}", *members);
let memberslice = std::slice::from_raw_parts((*members).members_, (*members).member_count_ as usize);
for member in memberslice {
println!("member: {:#?}", *member);
}
let msg_native = WrappedNativeMsg::<shape_msgs::msg::SolidPrimitive>::new();
let mut msg = shape_msgs::msg::SolidPrimitive::from_native(&msg_native);
println!("{:#?}", msg);
msg.dimensions.push(1.0);
msg.dimensions.push(1.0);
msg.dimensions.push(1.0);
msg.dimensions.push(1.0); // only three elements allowed
let msg_native2 = WrappedNativeMsg::<shape_msgs::msg::SolidPrimitive>::from(&msg);
}
}
#[test]
fn test_generation_string_use() -> () {
let msg = std_msgs::msg::String { data: "hej".into() };