Modulo 5.0.0
|
Modulo Core translation module for converting between ROS2 and state_representation data types. More...
Functions | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::Accel &message) |
Convert a ROS geometry_msgs::msg::Accel to a CartesianState. | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::AccelStamped &message) |
Convert a ROS geometry_msgs::msg::AccelStamped to a CartesianState. | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::Pose &message) |
Convert a ROS geometry_msgs::msg::Pose to a CartesianState. | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::PoseStamped &message) |
Convert a ROS geometry_msgs::msg::PoseStamped to a CartesianState. | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::Transform &message) |
Convert a ROS geometry_msgs::msg::Transform to a CartesianState. | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::TransformStamped &message) |
Convert a ROS geometry_msgs::msg::TransformStamped to a CartesianState. | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::Twist &message) |
Convert a ROS geometry_msgs::msg::Twist to a CartesianState. | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::TwistStamped &message) |
Convert a ROS geometry_msgs::msg::TwistStamped to a CartesianState. | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::Wrench &message) |
Convert a ROS geometry_msgs::msg::Wrench to a CartesianState. | |
void | read_message (state_representation::CartesianState &state, const geometry_msgs::msg::WrenchStamped &message) |
Convert a ROS geometry_msgs::msg::WrenchStamped to a CartesianState. | |
void | read_message (state_representation::JointState &state, const sensor_msgs::msg::JointState &message) |
Convert a ROS sensor_msgs::msg::JointState to a JointState. | |
template<typename T , typename U > | |
void | read_message (state_representation::Parameter< T > &state, const U &message) |
Template function to convert a ROS std_msgs::msg::T to a Parameter<T> | |
void | read_message (bool &state, const std_msgs::msg::Bool &message) |
Convert a ROS std_msgs::msg::Bool to a boolean. | |
void | read_message (double &state, const std_msgs::msg::Float64 &message) |
Convert a ROS std_msgs::msg::Float64 to a double. | |
void | read_message (std::vector< double > &state, const std_msgs::msg::Float64MultiArray &message) |
Convert a ROS std_msgs::msg::Float64MultiArray to a vector of double. | |
void | read_message (int &state, const std_msgs::msg::Int32 &message) |
Convert a ROS std_msgs::msg::Int32 to an integer. | |
void | read_message (std::string &state, const std_msgs::msg::String &message) |
Convert a ROS std_msgs::msg::String to a string. | |
template<typename T > | |
void | read_message (T &state, const EncodedState &message) |
Convert a ROS std_msgs::msg::UInt8MultiArray message to a State using protobuf decoding. | |
template<typename T > | |
std::shared_ptr< T > | safe_dynamic_pointer_cast (std::shared_ptr< state_representation::State > &state) |
Safely downcast a base state pointer to a derived state pointer. | |
template<typename T > | |
void | safe_dynamic_cast (std::shared_ptr< state_representation::State > &state, std::shared_ptr< state_representation::State > &new_state) |
Update the value referenced by a state pointer from a new_state pointer. | |
template<typename StateT , typename NewStateT > | |
void | safe_spatial_state_conversion (std::shared_ptr< state_representation::State > &state, std::shared_ptr< state_representation::State > &new_state, std::function< void(StateT &, const NewStateT &)> conversion_callback={}) |
Update the value referenced by a state pointer by dynamically casting and converting the value referenced by a new_state pointer. | |
template<typename StateT , typename NewStateT > | |
void | safe_state_with_names_conversion (std::shared_ptr< state_representation::State > &state, std::shared_ptr< state_representation::State > &new_state, std::function< void(StateT &, const NewStateT &)> conversion_callback={}) |
Update the value referenced by a state pointer by dynamically casting and converting the value referenced by a new_state pointer. | |
template<> | |
void | read_message (std::shared_ptr< state_representation::State > &state, const EncodedState &message) |
void | write_message (geometry_msgs::msg::Accel &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::Accel. | |
void | write_message (geometry_msgs::msg::AccelStamped &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::AccelStamped. | |
void | write_message (geometry_msgs::msg::Pose &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::Pose. | |
void | write_message (geometry_msgs::msg::PoseStamped &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::PoseStamped. | |
void | write_message (geometry_msgs::msg::Transform &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::Transform. | |
void | write_message (geometry_msgs::msg::TransformStamped &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::TransformStamped. | |
void | write_message (geometry_msgs::msg::Twist &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::Twist. | |
void | write_message (geometry_msgs::msg::TwistStamped &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::TwistStamped. | |
void | write_message (geometry_msgs::msg::Wrench &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::Wrench. | |
void | write_message (geometry_msgs::msg::WrenchStamped &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS geometry_msgs::msg::WrenchStamped. | |
void | write_message (sensor_msgs::msg::JointState &message, const state_representation::JointState &state, const rclcpp::Time &time) |
Convert a JointState to a ROS sensor_msgs::msg::JointState. | |
void | write_message (tf2_msgs::msg::TFMessage &message, const state_representation::CartesianState &state, const rclcpp::Time &time) |
Convert a CartesianState to a ROS tf2_msgs::msg::TFMessage. | |
template<typename U , typename T > | |
void | write_message (U &message, const state_representation::Parameter< T > &state, const rclcpp::Time &) |
Convert a Parameter<T> to a ROS equivalent representation. | |
void | write_message (std_msgs::msg::Bool &message, const bool &state, const rclcpp::Time &time) |
Convert a boolean to a ROS std_msgs::msg::Bool. | |
void | write_message (std_msgs::msg::Float64 &message, const double &state, const rclcpp::Time &time) |
Convert a double to a ROS std_msgs::msg::Float64. | |
void | write_message (std_msgs::msg::Float64MultiArray &message, const std::vector< double > &state, const rclcpp::Time &time) |
Convert a vector of double to a ROS std_msgs::msg::Float64MultiArray. | |
void | write_message (std_msgs::msg::Int32 &message, const int &state, const rclcpp::Time &time) |
Convert an integer to a ROS std_msgs::msg::Int32. | |
void | write_message (std_msgs::msg::String &message, const std::string &state, const rclcpp::Time &time) |
Convert a string to a ROS std_msgs::msg::String. | |
template<typename T > | |
void | write_message (EncodedState &message, const T &state, const rclcpp::Time &) |
Convert a state to an EncodedState (std_msgs::msg::UInt8MultiArray) message using protobuf encoding. | |
void | copy_parameter_value (const std::shared_ptr< const state_representation::ParameterInterface > &source_parameter, const std::shared_ptr< state_representation::ParameterInterface > ¶meter) |
Copy the value of one parameter interface into another. | |
rclcpp::Parameter | write_parameter (const std::shared_ptr< state_representation::ParameterInterface > ¶meter) |
Write a ROS Parameter from a ParameterInterface pointer. | |
std::shared_ptr< state_representation::ParameterInterface > | read_parameter (const rclcpp::Parameter &ros_parameter) |
Create a new ParameterInterface from a ROS Parameter object. | |
std::shared_ptr< state_representation::ParameterInterface > | read_parameter_const (const rclcpp::Parameter &ros_parameter, const std::shared_ptr< const state_representation::ParameterInterface > ¶meter) |
Update the parameter value of a ParameterInterface from a ROS Parameter object only if the two parameters have the same name and the ROS Parameter value can be interpreted as a ParameterInterface value. | |
void | read_parameter (const rclcpp::Parameter &ros_parameter, const std::shared_ptr< state_representation::ParameterInterface > ¶meter) |
Update the parameter value of a ParameterInterface from a ROS Parameter object. | |
rclcpp::ParameterType | get_ros_parameter_type (const state_representation::ParameterType ¶meter_type) |
Given a state representation parameter type, get the corresponding ROS parameter type. | |
void | write_message (geometry_msgs::msg::Accel &message, const CartesianState &state, const rclcpp::Time &) |
void | write_message (geometry_msgs::msg::AccelStamped &message, const CartesianState &state, const rclcpp::Time &time) |
void | write_message (geometry_msgs::msg::Pose &message, const CartesianState &state, const rclcpp::Time &) |
void | write_message (geometry_msgs::msg::PoseStamped &message, const CartesianState &state, const rclcpp::Time &time) |
void | write_message (geometry_msgs::msg::Transform &message, const CartesianState &state, const rclcpp::Time &) |
void | write_message (geometry_msgs::msg::TransformStamped &message, const CartesianState &state, const rclcpp::Time &time) |
void | write_message (geometry_msgs::msg::Twist &message, const CartesianState &state, const rclcpp::Time &) |
void | write_message (geometry_msgs::msg::TwistStamped &message, const CartesianState &state, const rclcpp::Time &time) |
void | write_message (geometry_msgs::msg::Wrench &message, const CartesianState &state, const rclcpp::Time &) |
void | write_message (geometry_msgs::msg::WrenchStamped &message, const CartesianState &state, const rclcpp::Time &time) |
void | write_message (sensor_msgs::msg::JointState &message, const JointState &state, const rclcpp::Time &time) |
void | write_message (tf2_msgs::msg::TFMessage &message, const CartesianState &state, const rclcpp::Time &time) |
template<typename U , typename T > | |
void | write_message (U &message, const Parameter< T > &state, const rclcpp::Time &) |
template void | write_message< std_msgs::msg::Float64, double > (std_msgs::msg::Float64 &message, const Parameter< double > &state, const rclcpp::Time &) |
template void | write_message< std_msgs::msg::Float64MultiArray, std::vector< double > > (std_msgs::msg::Float64MultiArray &message, const Parameter< std::vector< double > > &state, const rclcpp::Time &) |
template void | write_message< std_msgs::msg::Bool, bool > (std_msgs::msg::Bool &message, const Parameter< bool > &state, const rclcpp::Time &) |
template void | write_message< std_msgs::msg::String, std::string > (std_msgs::msg::String &message, const Parameter< std::string > &state, const rclcpp::Time &) |
template<> | |
void | write_message (geometry_msgs::msg::Transform &message, const Parameter< CartesianPose > &state, const rclcpp::Time &time) |
template<> | |
void | write_message (geometry_msgs::msg::TransformStamped &message, const Parameter< CartesianPose > &state, const rclcpp::Time &time) |
template<> | |
void | write_message (tf2_msgs::msg::TFMessage &message, const Parameter< CartesianPose > &state, const rclcpp::Time &time) |
void | copy_parameter_value (const std::shared_ptr< const ParameterInterface > &source_parameter, const std::shared_ptr< ParameterInterface > ¶meter) |
rclcpp::Parameter | write_parameter (const std::shared_ptr< ParameterInterface > ¶meter) |
std::shared_ptr< ParameterInterface > | read_parameter_const (const rclcpp::Parameter &ros_parameter, const std::shared_ptr< const ParameterInterface > ¶meter) |
void | read_parameter (const rclcpp::Parameter &ros_parameter, const std::shared_ptr< ParameterInterface > ¶meter) |
rclcpp::ParameterType | get_ros_parameter_type (const ParameterType ¶meter_type) |
Modulo Core translation module for converting between ROS2 and state_representation data types.
void modulo_core::translators::copy_parameter_value | ( | const std::shared_ptr< const ParameterInterface > & | source_parameter, |
const std::shared_ptr< ParameterInterface > & | parameter | ||
) |
Definition at line 15 of file parameter_translators.cpp.
void modulo_core::translators::copy_parameter_value | ( | const std::shared_ptr< const state_representation::ParameterInterface > & | source_parameter, |
const std::shared_ptr< state_representation::ParameterInterface > & | parameter | ||
) |
Copy the value of one parameter interface into another.
When referencing a Parameter instance through a ParameterInterface pointer, it is necessary to know the parameter type to get or set the parameter value. Sometimes it is desirable to update the parameter value from another compatible ParameterInterface, while still preserving the reference to the original instance. This helper function calls the getters and setters of the appropriate parameter type to modify the value of the parameter instance while preserving the reference of the original pointer.
source_parameter | The ParameterInterface with a value to copy |
parameter | The destination ParameterInterface to be updated |
modulo_core::exceptions::ParameterTranslationException | if the copying failed |
rclcpp::ParameterType modulo_core::translators::get_ros_parameter_type | ( | const ParameterType & | parameter_type | ) |
Definition at line 257 of file parameter_translators.cpp.
rclcpp::ParameterType modulo_core::translators::get_ros_parameter_type | ( | const state_representation::ParameterType & | parameter_type | ) |
Given a state representation parameter type, get the corresponding ROS parameter type.
parameter_type | The state representation parameter type |
void modulo_core::translators::read_message | ( | bool & | state, |
const std_msgs::msg::Bool & | message | ||
) |
Convert a ROS std_msgs::msg::Bool to a boolean.
state | The state to populate |
message | The ROS message to read from |
Definition at line 85 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | double & | state, |
const std_msgs::msg::Float64 & | message | ||
) |
Convert a ROS std_msgs::msg::Float64 to a double.
state | The state to populate |
message | The ROS message to read from |
Definition at line 89 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | int & | state, |
const std_msgs::msg::Int32 & | message | ||
) |
Convert a ROS std_msgs::msg::Int32 to an integer.
state | The state to populate |
message | The ROS message to read from |
Definition at line 97 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::Accel & | message | ||
) |
Convert a ROS geometry_msgs::msg::Accel to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 17 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::AccelStamped & | message | ||
) |
Convert a ROS geometry_msgs::msg::AccelStamped to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 22 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::Pose & | message | ||
) |
Convert a ROS geometry_msgs::msg::Pose to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 27 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::PoseStamped & | message | ||
) |
Convert a ROS geometry_msgs::msg::PoseStamped to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 32 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::Transform & | message | ||
) |
Convert a ROS geometry_msgs::msg::Transform to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 37 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::TransformStamped & | message | ||
) |
Convert a ROS geometry_msgs::msg::TransformStamped to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 42 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::Twist & | message | ||
) |
Convert a ROS geometry_msgs::msg::Twist to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 48 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::TwistStamped & | message | ||
) |
Convert a ROS geometry_msgs::msg::TwistStamped to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 53 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::Wrench & | message | ||
) |
Convert a ROS geometry_msgs::msg::Wrench to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 58 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::CartesianState & | state, |
const geometry_msgs::msg::WrenchStamped & | message | ||
) |
Convert a ROS geometry_msgs::msg::WrenchStamped to a CartesianState.
state | The CartesianState to populate |
message | The ROS message to read from |
Definition at line 63 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::JointState & | state, |
const sensor_msgs::msg::JointState & | message | ||
) |
Convert a ROS sensor_msgs::msg::JointState to a JointState.
state | The JointState to populate |
message | The ROS message to read from |
Definition at line 68 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | state_representation::Parameter< T > & | state, |
const U & | message | ||
) |
Template function to convert a ROS std_msgs::msg::T to a Parameter<T>
T | All types of parameters supported in ROS std messages |
U | All types of parameters supported in ROS std messages |
state | The Parameter<T> to populate |
message | The ROS message to read from |
Definition at line 115 of file message_readers.hpp.
|
inline |
Definition at line 275 of file message_readers.hpp.
void modulo_core::translators::read_message | ( | std::string & | state, |
const std_msgs::msg::String & | message | ||
) |
Convert a ROS std_msgs::msg::String to a string.
state | The state to populate |
message | The ROS message to read from |
Definition at line 101 of file message_readers.cpp.
void modulo_core::translators::read_message | ( | std::vector< double > & | state, |
const std_msgs::msg::Float64MultiArray & | message | ||
) |
Convert a ROS std_msgs::msg::Float64MultiArray to a vector of double.
state | The state to populate |
message | The ROS message to read from |
Definition at line 93 of file message_readers.cpp.
|
inline |
Convert a ROS std_msgs::msg::UInt8MultiArray message to a State using protobuf decoding.
T | A state_representation::State type |
state | The state to populate |
message | The ROS message to read from |
modulo_core::exceptions::MessageTranslationException | if the translation failed or is not supported. |
Definition at line 162 of file message_readers.hpp.
std::shared_ptr< ParameterInterface > modulo_core::translators::read_parameter | ( | const rclcpp::Parameter & | ros_parameter | ) |
Create a new ParameterInterface from a ROS Parameter object.
ros_parameter | The ROS parameter object to read |
modulo_core::exceptions::ParameterTranslationException | if the ROS parameter could not be read |
Definition at line 141 of file parameter_translators.cpp.
void modulo_core::translators::read_parameter | ( | const rclcpp::Parameter & | ros_parameter, |
const std::shared_ptr< ParameterInterface > & | parameter | ||
) |
Definition at line 252 of file parameter_translators.cpp.
void modulo_core::translators::read_parameter | ( | const rclcpp::Parameter & | ros_parameter, |
const std::shared_ptr< state_representation::ParameterInterface > & | parameter | ||
) |
Update the parameter value of a ParameterInterface from a ROS Parameter object.
The destination ParameterInterface must have a compatible parameter name and type.
ros_parameter | The ROS parameter object to read |
parameter | An existing ParameterInterface pointer |
modulo_core::exceptions::ParameterTranslationException | if the ROS parameter could not be read |
std::shared_ptr< ParameterInterface > modulo_core::translators::read_parameter_const | ( | const rclcpp::Parameter & | ros_parameter, |
const std::shared_ptr< const ParameterInterface > & | parameter | ||
) |
Definition at line 192 of file parameter_translators.cpp.
std::shared_ptr< state_representation::ParameterInterface > modulo_core::translators::read_parameter_const | ( | const rclcpp::Parameter & | ros_parameter, |
const std::shared_ptr< const state_representation::ParameterInterface > & | parameter | ||
) |
Update the parameter value of a ParameterInterface from a ROS Parameter object only if the two parameters have the same name and the ROS Parameter value can be interpreted as a ParameterInterface value.
ros_parameter | The ROS parameter object to read |
parameter | An existing ParameterInterface pointer |
modulo_core::exceptions::ParameterTranslationException | if the ROS parameter could not be read |
|
inline |
Update the value referenced by a state pointer from a new_state pointer.
The base state and new_state pointers must reference state-derived instances of type T. This function dynamically downcasts each pointer to a pointer of the derived type and assigns the de-referenced value from the new_state parameter to the address of the state pointer.
T | The derived state type |
state | A base state pointer referencing a state-derived instance to be modified |
new_state | A base state pointer referencing a state-derived instance to be copied into the state parameter |
modulo_core::exceptions::MessageTranslationException | if either parameter cannot be cast to state type T |
Definition at line 202 of file message_readers.hpp.
|
inline |
Safely downcast a base state pointer to a derived state pointer.
This utility function asserts that result of the dynamic pointer cast is not null, and throws an exception otherwise. This helps to prevent uncaught segmentation faults from a null pointer dynamic cast result being passed to subsequent execution steps.
T | The derived state type |
state | A base state pointer referencing a state-derived instance |
modulo_core::exceptions::MessageTranslationException | if the dynamic cast results in a null pointer |
Definition at line 182 of file message_readers.hpp.
|
inline |
Update the value referenced by a state pointer by dynamically casting and converting the value referenced by a new_state pointer.
This utility function is intended to help the conversion between spatial-state-derived instances encapsulated in base state pointers. It sets the name and reference frame of the referenced state instance from the new_state, and then passes the referenced values to a user-defined conversion callback function. For example, if state is referencing a CartesianPose instance A and new_state is referencing a CartesianState instance B, the conversion callback function should invoke A.set_pose(B.get_pose()).
StateT | The derived spatial state type of the destination state |
NewStateT | The derived spatial state type of the new state |
state | A base state pointer referencing a spatial-state-derived instance to be modified |
new_state | A base state pointer referencing a spatial-state-derived instance to be converted into the state parameter |
conversion_callback | A callback function taking parameters of type StateT and NewStateT, where the referenced StateT instance can be modified as needed from the NewStateT value |
Definition at line 226 of file message_readers.hpp.
|
inline |
Update the value referenced by a state pointer by dynamically casting and converting the value referenced by a new_state pointer.
This utility function is intended to help the conversion between joint-state-derived instances encapsulated in base state pointers. It sets the name and joint names of the referenced state instance from the new_state, and then passes the referenced values to a user-defined conversion callback function. For example, if state is referencing a JointPositions instance A and new_state is referencing a JointState instance B, the conversion callback function should invoke A.set_positions(B.get_positions()).
StateT | The derived joint state type of the destination state |
NewStateT | The derived joint state type of the new state |
state | A base state pointer referencing a joint-state-derived instance to be modified |
new_state | A base state pointer referencing a joint-state-derived instance to be converted into the state parameter |
conversion_callback | A callback function taking parameters of type StateT and NewStateT, where the referenced StateT instance can be modified as needed from the NewStateT value |
Definition at line 260 of file message_readers.hpp.
|
inline |
Convert a state to an EncodedState (std_msgs::msg::UInt8MultiArray) message using protobuf encoding.
T | A state_representation::State type |
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the translation failed or is not supported. |
Definition at line 215 of file message_writers.hpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Accel & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | |||
) |
Definition at line 28 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Accel & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::Accel.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | geometry_msgs::msg::AccelStamped & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 37 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::AccelStamped & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::AccelStamped.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Pose & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | |||
) |
Definition at line 43 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Pose & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::Pose.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | geometry_msgs::msg::PoseStamped & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 52 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::PoseStamped & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::PoseStamped.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Transform & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | |||
) |
Definition at line 58 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Transform & | message, |
const Parameter< CartesianPose > & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 152 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Transform & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::Transform.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | geometry_msgs::msg::TransformStamped & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 67 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::TransformStamped & | message, |
const Parameter< CartesianPose > & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 158 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::TransformStamped & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::TransformStamped.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Twist & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | |||
) |
Definition at line 75 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Twist & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::Twist.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | geometry_msgs::msg::TwistStamped & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 84 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::TwistStamped & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::TwistStamped.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Wrench & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | |||
) |
Definition at line 90 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::Wrench & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::Wrench.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | geometry_msgs::msg::WrenchStamped & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 99 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | geometry_msgs::msg::WrenchStamped & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS geometry_msgs::msg::WrenchStamped.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | sensor_msgs::msg::JointState & | message, |
const JointState & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 105 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | sensor_msgs::msg::JointState & | message, |
const state_representation::JointState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a JointState to a ROS sensor_msgs::msg::JointState.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | std_msgs::msg::Bool & | message, |
const bool & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a boolean to a ROS std_msgs::msg::Bool.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
Definition at line 168 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | std_msgs::msg::Float64 & | message, |
const double & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a double to a ROS std_msgs::msg::Float64.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
Definition at line 172 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | std_msgs::msg::Float64MultiArray & | message, |
const std::vector< double > & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a vector of double to a ROS std_msgs::msg::Float64MultiArray.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
Definition at line 176 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | std_msgs::msg::Int32 & | message, |
const int & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert an integer to a ROS std_msgs::msg::Int32.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
Definition at line 180 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | std_msgs::msg::String & | message, |
const std::string & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a string to a ROS std_msgs::msg::String.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
Definition at line 184 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | tf2_msgs::msg::TFMessage & | message, |
const CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 120 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | tf2_msgs::msg::TFMessage & | message, |
const Parameter< CartesianPose > & | state, | ||
const rclcpp::Time & | time | ||
) |
Definition at line 164 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | tf2_msgs::msg::TFMessage & | message, |
const state_representation::CartesianState & | state, | ||
const rclcpp::Time & | time | ||
) |
Convert a CartesianState to a ROS tf2_msgs::msg::TFMessage.
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
void modulo_core::translators::write_message | ( | U & | message, |
const Parameter< T > & | state, | ||
const rclcpp::Time & | |||
) |
Definition at line 131 of file message_writers.cpp.
void modulo_core::translators::write_message | ( | U & | message, |
const state_representation::Parameter< T > & | state, | ||
const rclcpp::Time & | |||
) |
Convert a Parameter<T> to a ROS equivalent representation.
T | All types of parameters supported in ROS std messages |
U | All types of parameters supported in ROS std messages |
message | The ROS message to populate |
state | The state to read from |
time | The time of the message |
modulo_core::exceptions::MessageTranslationException | if the provided state is empty. |
rclcpp::Parameter modulo_core::translators::write_parameter | ( | const std::shared_ptr< ParameterInterface > & | parameter | ) |
Definition at line 89 of file parameter_translators.cpp.
rclcpp::Parameter modulo_core::translators::write_parameter | ( | const std::shared_ptr< state_representation::ParameterInterface > & | parameter | ) |
Write a ROS Parameter from a ParameterInterface pointer.
parameter | The ParameterInterface pointer with a name and value |
modulo_core::exceptions::ParameterTranslationException | if the ROS parameter could not be written |