1#ifndef WBC_ROS_CONVERSIONS_HPP
2#define WBC_ROS_CONVERSIONS_HPP
4#include <rclcpp/rclcpp.hpp>
5#include <geometry_msgs/msg/twist.hpp>
6#include <geometry_msgs/msg/wrench.hpp>
7#include <std_msgs/msg/float64_multi_array.hpp>
8#include <robot_control_msgs/msg/rigid_body_state.hpp>
9#include <robot_control_msgs/msg/joint_command.hpp>
10#include <robot_control_msgs/msg/joint_state.hpp>
11#include <robot_control_msgs/msg/robot_state.hpp>
12#include <robot_control_msgs/msg/contacts.hpp>
14#include <wbc/types/JointState.hpp>
15#include <wbc/types/JointCommand.hpp>
16#include <wbc/types/RigidBodyState.hpp>
17#include <wbc/types/Wrench.hpp>
18#include <wbc/types/Contact.hpp>
20void fromROS(
const geometry_msgs::msg::Pose& in, wbc::types::Pose& out);
21void fromROS(
const geometry_msgs::msg::Twist& in, wbc::types::Twist& out);
22void fromROS(
const geometry_msgs::msg::Accel& in, wbc::types::SpatialAcceleration& out);
23void fromROS(
const geometry_msgs::msg::Wrench& in, wbc::types::Wrench& out);
24void fromROS(
const robot_control_msgs::msg::JointState& in,
const std::vector<int>& joint_indices, wbc::types::JointState& out);
25void fromROS(
const robot_control_msgs::msg::RigidBodyState& in, wbc::types::RigidBodyState& out);
26void fromROS(
const robot_control_msgs::msg::JointCommand& in,
const std::vector<int>& joint_indices, wbc::types::JointCommand& out);
27void fromROS(
const robot_control_msgs::msg::Contacts& in, std::vector<wbc::types::Contact>& out);
28void fromROS(
const std_msgs::msg::Float64MultiArray& in, Eigen::VectorXd& out);
29void fromROS(
const robot_control_msgs::msg::RobotState& in,
const std::vector<int>& joint_indices,
30 wbc::types::JointState &joint_state_out, wbc::types::RigidBodyState& floating_base_state_out);
32void toROS(
const wbc::types::RigidBodyState& in, robot_control_msgs::msg::RigidBodyState& out);
33void toROS(
const wbc::types::JointCommand& in,
const std::vector<int>& joint_indices, robot_control_msgs::msg::JointCommand& out);
34void toROS(
const wbc::types::JointCommand& in,
const std::vector<double> &kp,
const std::vector<double> &kd,
const std::vector<int>& joint_indices,
35 robot_control_msgs::msg::JointCommand& out);
36void toROS(
const Eigen::VectorXd& in, std_msgs::msg::Float64MultiArray& out);
37void toROS(
const wbc::types::Pose& in, geometry_msgs::msg::Pose& out);
38void toROS(
const wbc::types::Twist& in, geometry_msgs::msg::Twist& out);
39void toROS(
const wbc::types::SpatialAcceleration& in, geometry_msgs::msg::Accel& out);
40void toROS(
const wbc::types::Pose& pose,
const wbc::types::Twist& twist,
const wbc::types::SpatialAcceleration& acc, robot_control_msgs::msg::RigidBodyState& out);
41void toROS(
const wbc::types::JointState& in,
const std::vector<int>& joint_indices, robot_control_msgs::msg::JointState& out);
void toROS(const wbc::types::RigidBodyState &in, robot_control_msgs::msg::RigidBodyState &out)
Definition conversions.cpp:78
void fromROS(const geometry_msgs::msg::Pose &in, wbc::types::Pose &out)
Definition conversions.cpp:7