Skip to content

Commit

Permalink
Fixed sized arrays <=32 members working
Browse files Browse the repository at this point in the history
  • Loading branch information
carter committed Feb 8, 2024
1 parent 113df2c commit 1a2b2a6
Show file tree
Hide file tree
Showing 5 changed files with 51 additions and 29 deletions.
3 changes: 2 additions & 1 deletion roslibrust_codegen/src/gen.rs
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,8 @@ fn generate_field_definition(
.to_owned(),
};
let rust_field_type = match field.field_type.array_info {
Some(_) => format!("::std::vec::Vec<{rust_field_type}>"),
Some(None) => format!("::std::vec::Vec<{rust_field_type}>"),
Some(Some(fixed_length)) => format!("[{rust_field_type}; {fixed_length}]"),
None => rust_field_type,
};
let rust_field_type = TokenStream::from_str(rust_field_type.as_str()).expect(
Expand Down
2 changes: 1 addition & 1 deletion roslibrust_codegen/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -631,7 +631,7 @@ fn parse_ros_files(

#[cfg(test)]
mod test {
use crate::find_and_generate_ros_messages;
use crate::{find_and_generate_ros_messages, FieldInfo};

/// Confirms we don't panic on ros1 parsing
#[test_log::test]
Expand Down
21 changes: 21 additions & 0 deletions roslibrust_codegen/src/parse/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -216,3 +216,24 @@ fn parse_type(type_str: &str, pkg: &Package) -> Result<FieldType, Error> {
}
}
}

#[cfg(test)]
mod test {
use crate::{
parse::parse_type,
utils::{Package, RosVersion},
};

// Simple test to just confirm fixed size logic is working correctly on the parse side
#[test_log::test]
fn parse_type_handles_fixed_size_correctly() {
let line = "int32[9]";
let pkg = Package {
name: "test_pkg".to_string(),
path: "./not_a_path".into(),
version: Some(RosVersion::ROS1),
};
let parsed = parse_type(line, &pkg).unwrap();
assert_eq!(parsed.array_info, Some(Some(9)));
}
}
26 changes: 13 additions & 13 deletions roslibrust_test/src/ros1.rs
Original file line number Diff line number Diff line change
Expand Up @@ -306,7 +306,7 @@ pub mod geometry_msgs {
)]
pub struct AccelWithCovariance {
pub r#accel: self::Accel,
pub r#covariance: ::std::vec::Vec<f64>,
pub r#covariance: [f64; 36],
}
impl ::roslibrust_codegen::RosMessageType for AccelWithCovariance {
const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovariance";
Expand Down Expand Up @@ -549,7 +549,7 @@ pub mod geometry_msgs {
)]
pub struct PoseWithCovariance {
pub r#pose: self::Pose,
pub r#covariance: ::std::vec::Vec<f64>,
pub r#covariance: [f64; 36],
}
impl ::roslibrust_codegen::RosMessageType for PoseWithCovariance {
const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovariance";
Expand Down Expand Up @@ -697,7 +697,7 @@ pub mod geometry_msgs {
)]
pub struct TwistWithCovariance {
pub r#twist: self::Twist,
pub r#covariance: ::std::vec::Vec<f64>,
pub r#covariance: [f64; 36],
}
impl ::roslibrust_codegen::RosMessageType for TwistWithCovariance {
const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovariance";
Expand Down Expand Up @@ -2443,9 +2443,9 @@ pub mod sensor_msgs {
pub r#width: u32,
pub r#distortion_model: ::std::string::String,
pub r#D: ::std::vec::Vec<f64>,
pub r#K: ::std::vec::Vec<f64>,
pub r#R: ::std::vec::Vec<f64>,
pub r#P: ::std::vec::Vec<f64>,
pub r#K: [f64; 9],
pub r#R: [f64; 9],
pub r#P: [f64; 12],
pub r#binning_x: u32,
pub r#binning_y: u32,
pub r#roi: self::RegionOfInterest,
Expand Down Expand Up @@ -2565,11 +2565,11 @@ pub mod sensor_msgs {
pub struct Imu {
pub r#header: std_msgs::Header,
pub r#orientation: geometry_msgs::Quaternion,
pub r#orientation_covariance: ::std::vec::Vec<f64>,
pub r#orientation_covariance: [f64; 9],
pub r#angular_velocity: geometry_msgs::Vector3,
pub r#angular_velocity_covariance: ::std::vec::Vec<f64>,
pub r#angular_velocity_covariance: [f64; 9],
pub r#linear_acceleration: geometry_msgs::Vector3,
pub r#linear_acceleration_covariance: ::std::vec::Vec<f64>,
pub r#linear_acceleration_covariance: [f64; 9],
}
impl ::roslibrust_codegen::RosMessageType for Imu {
const ROS_TYPE_NAME: &'static str = "sensor_msgs/Imu";
Expand Down Expand Up @@ -2713,7 +2713,7 @@ pub mod sensor_msgs {
pub struct MagneticField {
pub r#header: std_msgs::Header,
pub r#magnetic_field: geometry_msgs::Vector3,
pub r#magnetic_field_covariance: ::std::vec::Vec<f64>,
pub r#magnetic_field_covariance: [f64; 9],
}
impl ::roslibrust_codegen::RosMessageType for MagneticField {
const ROS_TYPE_NAME: &'static str = "sensor_msgs/MagneticField";
Expand Down Expand Up @@ -2782,7 +2782,7 @@ pub mod sensor_msgs {
pub r#latitude: f64,
pub r#longitude: f64,
pub r#altitude: f64,
pub r#position_covariance: ::std::vec::Vec<f64>,
pub r#position_covariance: [f64; 9],
pub r#position_covariance_type: u8,
}
impl ::roslibrust_codegen::RosMessageType for NavSatFix {
Expand Down Expand Up @@ -3088,7 +3088,7 @@ pub mod shape_msgs {
PartialEq,
)]
pub struct MeshTriangle {
pub r#vertex_indices: ::std::vec::Vec<u32>,
pub r#vertex_indices: [u32; 3],
}
impl ::roslibrust_codegen::RosMessageType for MeshTriangle {
const ROS_TYPE_NAME: &'static str = "shape_msgs/MeshTriangle";
Expand All @@ -3106,7 +3106,7 @@ pub mod shape_msgs {
PartialEq,
)]
pub struct Plane {
pub r#coef: ::std::vec::Vec<f64>,
pub r#coef: [f64; 4],
}
impl ::roslibrust_codegen::RosMessageType for Plane {
const ROS_TYPE_NAME: &'static str = "shape_msgs/Plane";
Expand Down
28 changes: 14 additions & 14 deletions roslibrust_test/src/ros2.rs
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,7 @@ pub mod geometry_msgs {
)]
pub struct AccelWithCovariance {
pub r#accel: self::Accel,
pub r#covariance: ::std::vec::Vec<f64>,
pub r#covariance: [f64; 36],
}
impl ::roslibrust_codegen::RosMessageType for AccelWithCovariance {
const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovariance";
Expand Down Expand Up @@ -541,7 +541,7 @@ pub mod geometry_msgs {
)]
pub struct PoseWithCovariance {
pub r#pose: self::Pose,
pub r#covariance: ::std::vec::Vec<f64>,
pub r#covariance: [f64; 36],
}
impl ::roslibrust_codegen::RosMessageType for PoseWithCovariance {
const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovariance";
Expand Down Expand Up @@ -692,7 +692,7 @@ pub mod geometry_msgs {
)]
pub struct TwistWithCovariance {
pub r#twist: self::Twist,
pub r#covariance: ::std::vec::Vec<f64>,
pub r#covariance: [f64; 36],
}
impl ::roslibrust_codegen::RosMessageType for TwistWithCovariance {
const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovariance";
Expand Down Expand Up @@ -1162,9 +1162,9 @@ pub mod sensor_msgs {
pub r#width: u32,
pub r#distortion_model: ::std::string::String,
pub r#d: ::std::vec::Vec<f64>,
pub r#k: ::std::vec::Vec<f64>,
pub r#r: ::std::vec::Vec<f64>,
pub r#p: ::std::vec::Vec<f64>,
pub r#k: [f64; 9],
pub r#r: [f64; 9],
pub r#p: [f64; 12],
pub r#binning_x: u32,
pub r#binning_y: u32,
pub r#roi: self::RegionOfInterest,
Expand Down Expand Up @@ -1284,11 +1284,11 @@ pub mod sensor_msgs {
pub struct Imu {
pub r#header: std_msgs::Header,
pub r#orientation: geometry_msgs::Quaternion,
pub r#orientation_covariance: ::std::vec::Vec<f64>,
pub r#orientation_covariance: [f64; 9],
pub r#angular_velocity: geometry_msgs::Vector3,
pub r#angular_velocity_covariance: ::std::vec::Vec<f64>,
pub r#angular_velocity_covariance: [f64; 9],
pub r#linear_acceleration: geometry_msgs::Vector3,
pub r#linear_acceleration_covariance: ::std::vec::Vec<f64>,
pub r#linear_acceleration_covariance: [f64; 9],
}
impl ::roslibrust_codegen::RosMessageType for Imu {
const ROS_TYPE_NAME: &'static str = "sensor_msgs/Imu";
Expand Down Expand Up @@ -1432,7 +1432,7 @@ pub mod sensor_msgs {
pub struct MagneticField {
pub r#header: std_msgs::Header,
pub r#magnetic_field: geometry_msgs::Vector3,
pub r#magnetic_field_covariance: ::std::vec::Vec<f64>,
pub r#magnetic_field_covariance: [f64; 9],
}
impl ::roslibrust_codegen::RosMessageType for MagneticField {
const ROS_TYPE_NAME: &'static str = "sensor_msgs/MagneticField";
Expand Down Expand Up @@ -1501,7 +1501,7 @@ pub mod sensor_msgs {
pub r#latitude: f64,
pub r#longitude: f64,
pub r#altitude: f64,
pub r#position_covariance: ::std::vec::Vec<f64>,
pub r#position_covariance: [f64; 9],
pub r#position_covariance_type: u8,
}
impl ::roslibrust_codegen::RosMessageType for NavSatFix {
Expand Down Expand Up @@ -1805,7 +1805,7 @@ pub mod shape_msgs {
PartialEq,
)]
pub struct MeshTriangle {
pub r#vertex_indices: ::std::vec::Vec<u32>,
pub r#vertex_indices: [u32; 3],
}
impl ::roslibrust_codegen::RosMessageType for MeshTriangle {
const ROS_TYPE_NAME: &'static str = "shape_msgs/MeshTriangle";
Expand All @@ -1823,7 +1823,7 @@ pub mod shape_msgs {
PartialEq,
)]
pub struct Plane {
pub r#coef: ::std::vec::Vec<f64>,
pub r#coef: [f64; 4],
}
impl ::roslibrust_codegen::RosMessageType for Plane {
const ROS_TYPE_NAME: &'static str = "shape_msgs/Plane";
Expand All @@ -1841,7 +1841,7 @@ pub mod shape_msgs {
)]
pub struct SolidPrimitive {
pub r#type: u8,
pub r#dimensions: ::std::vec::Vec<f64>,
pub r#dimensions: [f64; 0],
pub r#polygon: geometry_msgs::Polygon,
}
impl ::roslibrust_codegen::RosMessageType for SolidPrimitive {
Expand Down

0 comments on commit 1a2b2a6

Please sign in to comment.