Giter Club home page Giter Club logo

ros-nalgebra's Introduction

ros-nalgebra

Build Status crates.io docs

Generate code to convert geometry_msgs into nalgebra structs, for rosrust.

Pre-requirements & dependencies

How to use

Easy usage: ros_nalgebra::rosmsg_include!()

Use ros_nalgebra::rosmsg_include instead of rosrust::rosmsg_include in your code.

use nalgebra as na;

mod msg {
    ros_nalgebra::rosmsg_include!(nav_msgs / Odometry);
}

fn main() {
    let mut odom_msg = msg::nav_msgs::Odometry::default();
    odom_msg.pose.pose.position.x = 1.0;
    odom_msg.pose.pose.position.y = -1.0;
    odom_msg.pose.pose.position.z = 2.0;
    odom_msg.pose.pose.orientation.x = 0.0;
    odom_msg.pose.pose.orientation.y = 0.0;
    odom_msg.pose.pose.orientation.z = 0.0;
    odom_msg.pose.pose.orientation.w = 1.0;

    // convert into nalgebra::Isometry<f64> by `from()`
    let pose = na::Isometry3::from(odom_msg.pose.pose);
    println!("{}", pose);

    let mut pose2 = pose.clone();
    pose2.translation.vector.x = -5.0;

    // convert into ROS msg using `into()`
    let pose_msg: msg::geometry_msgs::Pose = pose2.into();
    println!("{:?}", pose_msg);
}

Automatically defined messages by ros_nalgebra::rosmsg_include!()

Below messages are automatically included by ros_nalgebra::rosmsg_include!(). Do not include them in your code.

geometry_msgs/Point,
geometry_msgs/Pose,
geometry_msgs/Quaternion,
geometry_msgs/Transform,
geometry_msgs/Vector3,

Other usage: ros_nalgebra!() and ros_nalgebra_msg!()

If some messages are included already (for example in other crate), you can use ros_nalgebra_msg!(). The arguments are the rust namespace of the geometry_msgs (example:msg) and the message type (example: Pose for geometry_msgs/Pose, Point for geometry_msgs/Point).

Example

In some_other_crate,

mode msg {
  rosrust::rosmsg_include!(geometry_msgs/Point);
}

Then you can use ros_nalgebra::ros_nalgebra_msg!() in your crate.

// generate conversion code only for `geometry_msgs/Point` which is defined in `::some_other_crate::msg`.
ros_nalgebra::ros_nalgebra_msg!(::some_other_crate::msg, Point);

Supported conversions

See lib.rs.

TODO

Handle dependencies.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.