4#include <rclcpp/rclcpp.hpp>
5#include <sensor_msgs/msg/joint_state.hpp>
6#include <geometry_msgs/msg/twist_stamped.hpp>
7#include <trajectory_msgs/msg/joint_trajectory.hpp>
8#include <std_msgs/msg/float64_multi_array.hpp>
9#include <wbc_msgs/msg/rigid_body_state.hpp>
10#include <wbc_msgs/msg/task_config.hpp>
11#include <wbc_msgs/msg/task_status.hpp>
12#include <wbc_msgs/msg/radial_potential_field_vector.hpp>
13#include <geometry_msgs/msg/wrench_stamped.hpp>
15#include <base/samples/RigidBodyStateSE3.hpp>
16#include <base/commands/Joints.hpp>
17#include <base/samples/Wrench.hpp>
18#include <base/JointLimits.hpp>
19#include <wbc/core/TaskConfig.hpp>
20#include <wbc/core/TaskStatus.hpp>
21#include <wbc/core/RobotModelConfig.hpp>
22#include <wbc/core/QuadraticProgram.hpp>
24void fromROS(
const sensor_msgs::msg::JointState& in, base::samples::Joints& out);
25void fromROS(
const geometry_msgs::msg::Pose& in, base::Pose& out);
26void fromROS(
const geometry_msgs::msg::Twist& in, base::Twist& out);
27void fromROS(
const geometry_msgs::msg::Accel& in, base::Acceleration& out);
28void fromROS(
const wbc_msgs::msg::RigidBodyState& in, base::samples::RigidBodyStateSE3& out);
29void fromROS(
const trajectory_msgs::msg::JointTrajectory& in, base::samples::Joints& out);
30void fromROS(
const std_msgs::msg::Float64MultiArray& in, base::VectorXd& out);
31void fromROS(
const std_msgs::msg::Float64MultiArray& in,
const std::vector<std::string>& joint_names, wbc::JointWeights& out);
32void fromROS(
const geometry_msgs::msg::WrenchStamped& in, base::samples::Wrench& out);
33void toROS(
const base::commands::Joints& in, trajectory_msgs::msg::JointTrajectory& out);
34void toROS(
const base::VectorXd& in, std_msgs::msg::Float64MultiArray& out);
35void toROS(
const base::Pose& in, geometry_msgs::msg::Pose& out);
36void toROS(
const base::Twist& in, geometry_msgs::msg::Twist& out);
37void toROS(
const base::Acceleration& in, geometry_msgs::msg::Accel& out);
38void toROS(
const base::samples::RigidBodyStateSE3& in, wbc_msgs::msg::RigidBodyState& out);
39void toROS(
const base::samples::Joints& in, sensor_msgs::msg::JointState& out);
40void toROS(
const wbc::TaskConfig& in, wbc_msgs::msg::TaskConfig& out);
41void toROS(
const wbc::TaskStatus& in, wbc_msgs::msg::TaskStatus& out);
42void toROS(
const base::Time& in, builtin_interfaces::msg::Time& out);
43void toRaw(
const wbc_msgs::msg::RigidBodyState& in, std::vector<double> &out);
44void toRaw(
const trajectory_msgs::msg::JointTrajectory& in, std::vector<double> &out);
45void fromRaw(
const std::vector<double>& in, base::samples::RigidBodyStateSE3& out);
46void fromRaw(
const std::vector<double>& in, base::samples::Joints& out);
void toRaw(const wbc_msgs::msg::RigidBodyState &in, std::vector< double > &out)
Definition conversions.cpp:191
void toROS(const base::commands::Joints &in, trajectory_msgs::msg::JointTrajectory &out)
Definition conversions.cpp:81
void fromROS(const sensor_msgs::msg::JointState &in, base::samples::Joints &out)
Definition conversions.cpp:7
void fromRaw(const std::vector< double > &in, base::samples::RigidBodyStateSE3 &out)
Definition conversions.cpp:209