Trait r2r::WrappedTypesupport

source ·
pub trait WrappedTypesupport:
    Serialize
    + for<'de> Deserialize<'de>
    + Default
    + Debug
    + Clone {
    type CStruct;

    // Required methods
    fn get_ts() -> &'static rosidl_message_type_support_t;
    fn create_msg() -> *mut Self::CStruct;
    fn destroy_msg(msg: *mut Self::CStruct);
    fn from_native(msg: &Self::CStruct) -> Self;
    fn copy_to_native(&self, msg: &mut Self::CStruct);

    // Provided methods
    fn to_serialized_bytes(&self) -> Result<Vec<u8>> { ... }
    fn from_serialized_bytes(data: &[u8]) -> Result<Self> { ... }
}

Required Associated Types§

Required Methods§

source

fn get_ts() -> &'static rosidl_message_type_support_t

source

fn create_msg() -> *mut Self::CStruct

source

fn destroy_msg(msg: *mut Self::CStruct)

source

fn from_native(msg: &Self::CStruct) -> Self

source

fn copy_to_native(&self, msg: &mut Self::CStruct)

Provided Methods§

source

fn to_serialized_bytes(&self) -> Result<Vec<u8>>

This serializes the message using ROS2 methods.

source

fn from_serialized_bytes(data: &[u8]) -> Result<Self>

This deserializes the message using ROS2 methods.

Object Safety§

This trait is not object safe.

Implementors§

source§

impl WrappedTypesupport for AckermannDrive

source§

impl WrappedTypesupport for AckermannDriveStamped

source§

impl WrappedTypesupport for GoalInfo

source§

impl WrappedTypesupport for r2r::action_msgs::msg::GoalStatus

source§

impl WrappedTypesupport for r2r::action_msgs::msg::GoalStatusArray

source§

impl WrappedTypesupport for r2r::action_msgs::srv::CancelGoal::Request

source§

impl WrappedTypesupport for r2r::action_msgs::srv::CancelGoal::Response

source§

impl WrappedTypesupport for GoalID

source§

impl WrappedTypesupport for r2r::actionlib_msgs::msg::GoalStatus

source§

impl WrappedTypesupport for r2r::actionlib_msgs::msg::GoalStatusArray

source§

impl WrappedTypesupport for Duration

source§

impl WrappedTypesupport for Time

source§

impl WrappedTypesupport for r2r::composition_interfaces::srv::ListNodes::Request

source§

impl WrappedTypesupport for r2r::composition_interfaces::srv::ListNodes::Response

source§

impl WrappedTypesupport for r2r::composition_interfaces::srv::LoadNode::Request

source§

impl WrappedTypesupport for r2r::composition_interfaces::srv::LoadNode::Response

source§

impl WrappedTypesupport for r2r::composition_interfaces::srv::UnloadNode::Request

source§

impl WrappedTypesupport for r2r::composition_interfaces::srv::UnloadNode::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::FollowJointTrajectory::GetResult::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::FollowJointTrajectory::GetResult::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::FollowJointTrajectory::SendGoal::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::FollowJointTrajectory::SendGoal::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::FollowJointTrajectory::Feedback

source§

impl WrappedTypesupport for r2r::control_msgs::action::FollowJointTrajectory::FeedbackMessage

source§

impl WrappedTypesupport for r2r::control_msgs::action::FollowJointTrajectory::Goal

source§

impl WrappedTypesupport for r2r::control_msgs::action::FollowJointTrajectory::Result

source§

impl WrappedTypesupport for r2r::control_msgs::action::GripperCommand::GetResult::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::GripperCommand::GetResult::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::GripperCommand::SendGoal::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::GripperCommand::SendGoal::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::GripperCommand::Feedback

source§

impl WrappedTypesupport for r2r::control_msgs::action::GripperCommand::FeedbackMessage

source§

impl WrappedTypesupport for r2r::control_msgs::action::GripperCommand::Goal

source§

impl WrappedTypesupport for r2r::control_msgs::action::GripperCommand::Result

source§

impl WrappedTypesupport for r2r::control_msgs::action::JointTrajectory::GetResult::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::JointTrajectory::GetResult::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::JointTrajectory::SendGoal::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::JointTrajectory::SendGoal::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::JointTrajectory::Feedback

source§

impl WrappedTypesupport for r2r::control_msgs::action::JointTrajectory::FeedbackMessage

source§

impl WrappedTypesupport for r2r::control_msgs::action::JointTrajectory::Goal

source§

impl WrappedTypesupport for r2r::control_msgs::action::JointTrajectory::Result

source§

impl WrappedTypesupport for r2r::control_msgs::action::ParallelGripperCommand::GetResult::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::ParallelGripperCommand::GetResult::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::ParallelGripperCommand::SendGoal::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::ParallelGripperCommand::SendGoal::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::ParallelGripperCommand::Feedback

source§

impl WrappedTypesupport for r2r::control_msgs::action::ParallelGripperCommand::FeedbackMessage

source§

impl WrappedTypesupport for r2r::control_msgs::action::ParallelGripperCommand::Goal

source§

impl WrappedTypesupport for r2r::control_msgs::action::ParallelGripperCommand::Result

source§

impl WrappedTypesupport for r2r::control_msgs::action::PointHead::GetResult::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::PointHead::GetResult::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::PointHead::SendGoal::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::PointHead::SendGoal::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::PointHead::Feedback

source§

impl WrappedTypesupport for r2r::control_msgs::action::PointHead::FeedbackMessage

source§

impl WrappedTypesupport for r2r::control_msgs::action::PointHead::Goal

source§

impl WrappedTypesupport for r2r::control_msgs::action::PointHead::Result

source§

impl WrappedTypesupport for r2r::control_msgs::action::SingleJointPosition::GetResult::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::SingleJointPosition::GetResult::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::SingleJointPosition::SendGoal::Request

source§

impl WrappedTypesupport for r2r::control_msgs::action::SingleJointPosition::SendGoal::Response

source§

impl WrappedTypesupport for r2r::control_msgs::action::SingleJointPosition::Feedback

source§

impl WrappedTypesupport for r2r::control_msgs::action::SingleJointPosition::FeedbackMessage

source§

impl WrappedTypesupport for r2r::control_msgs::action::SingleJointPosition::Goal

source§

impl WrappedTypesupport for r2r::control_msgs::action::SingleJointPosition::Result

source§

impl WrappedTypesupport for AdmittanceControllerState

source§

impl WrappedTypesupport for DynamicJointState

source§

impl WrappedTypesupport for GripperCommand

source§

impl WrappedTypesupport for InterfaceValue

source§

impl WrappedTypesupport for JointComponentTolerance

source§

impl WrappedTypesupport for JointControllerState

source§

impl WrappedTypesupport for JointJog

source§

impl WrappedTypesupport for JointTolerance

source§

impl WrappedTypesupport for JointTrajectoryControllerState

source§

impl WrappedTypesupport for MecanumDriveControllerState

source§

impl WrappedTypesupport for MultiDOFCommand

source§

impl WrappedTypesupport for MultiDOFStateStamped

source§

impl WrappedTypesupport for PidState

source§

impl WrappedTypesupport for SingleDOFState

source§

impl WrappedTypesupport for SingleDOFStateStamped

source§

impl WrappedTypesupport for SteeringControllerStatus

source§

impl WrappedTypesupport for r2r::control_msgs::srv::QueryCalibrationState::Request

source§

impl WrappedTypesupport for r2r::control_msgs::srv::QueryCalibrationState::Response

source§

impl WrappedTypesupport for r2r::control_msgs::srv::QueryTrajectoryState::Request

source§

impl WrappedTypesupport for r2r::control_msgs::srv::QueryTrajectoryState::Response

source§

impl WrappedTypesupport for ChainConnection

source§

impl WrappedTypesupport for ControllerState

source§

impl WrappedTypesupport for HardwareComponentState

source§

impl WrappedTypesupport for HardwareInterface

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ConfigureController::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ConfigureController::Response

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ListControllerTypes::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ListControllerTypes::Response

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ListControllers::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ListControllers::Response

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ListHardwareComponents::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ListHardwareComponents::Response

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ListHardwareInterfaces::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ListHardwareInterfaces::Response

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::LoadController::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::LoadController::Response

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ReloadControllerLibraries::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::ReloadControllerLibraries::Response

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::SetHardwareComponentState::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::SetHardwareComponentState::Response

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::SwitchController::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::SwitchController::Response

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::UnloadController::Request

source§

impl WrappedTypesupport for r2r::controller_manager_msgs::srv::UnloadController::Response

source§

impl WrappedTypesupport for DiagnosticArray

source§

impl WrappedTypesupport for DiagnosticStatus

source§

impl WrappedTypesupport for KeyValue

source§

impl WrappedTypesupport for r2r::diagnostic_msgs::srv::AddDiagnostics::Request

source§

impl WrappedTypesupport for r2r::diagnostic_msgs::srv::AddDiagnostics::Response

source§

impl WrappedTypesupport for r2r::diagnostic_msgs::srv::SelfTest::Request

source§

impl WrappedTypesupport for r2r::diagnostic_msgs::srv::SelfTest::Response

source§

impl WrappedTypesupport for Accel

source§

impl WrappedTypesupport for AccelStamped

source§

impl WrappedTypesupport for AccelWithCovariance

source§

impl WrappedTypesupport for AccelWithCovarianceStamped

source§

impl WrappedTypesupport for Inertia

source§

impl WrappedTypesupport for InertiaStamped

source§

impl WrappedTypesupport for Point32

source§

impl WrappedTypesupport for Point

source§

impl WrappedTypesupport for PointStamped

source§

impl WrappedTypesupport for Polygon

source§

impl WrappedTypesupport for PolygonStamped

source§

impl WrappedTypesupport for Pose2D

source§

impl WrappedTypesupport for Pose

source§

impl WrappedTypesupport for PoseArray

source§

impl WrappedTypesupport for PoseStamped

source§

impl WrappedTypesupport for PoseWithCovariance

source§

impl WrappedTypesupport for PoseWithCovarianceStamped

source§

impl WrappedTypesupport for Quaternion

source§

impl WrappedTypesupport for QuaternionStamped

source§

impl WrappedTypesupport for Transform

source§

impl WrappedTypesupport for TransformStamped

source§

impl WrappedTypesupport for Twist

source§

impl WrappedTypesupport for TwistStamped

source§

impl WrappedTypesupport for TwistWithCovariance

source§

impl WrappedTypesupport for TwistWithCovarianceStamped

source§

impl WrappedTypesupport for Vector3

source§

impl WrappedTypesupport for Vector3Stamped

source§

impl WrappedTypesupport for VelocityStamped

source§

impl WrappedTypesupport for Wrench

source§

impl WrappedTypesupport for WrenchStamped

source§

impl WrappedTypesupport for State

source§

impl WrappedTypesupport for Transition

source§

impl WrappedTypesupport for TransitionDescription

source§

impl WrappedTypesupport for TransitionEvent

source§

impl WrappedTypesupport for r2r::lifecycle_msgs::srv::ChangeState::Request

source§

impl WrappedTypesupport for r2r::lifecycle_msgs::srv::ChangeState::Response

source§

impl WrappedTypesupport for r2r::lifecycle_msgs::srv::GetAvailableStates::Request

source§

impl WrappedTypesupport for r2r::lifecycle_msgs::srv::GetAvailableStates::Response

source§

impl WrappedTypesupport for r2r::lifecycle_msgs::srv::GetAvailableTransitions::Request

source§

impl WrappedTypesupport for r2r::lifecycle_msgs::srv::GetAvailableTransitions::Response

source§

impl WrappedTypesupport for r2r::lifecycle_msgs::srv::GetState::Request

source§

impl WrappedTypesupport for r2r::lifecycle_msgs::srv::GetState::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::AssistedTeleop::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::AssistedTeleop::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::AssistedTeleop::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::AssistedTeleop::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::AssistedTeleop::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::AssistedTeleop::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::AssistedTeleop::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::AssistedTeleop::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::BackUp::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::BackUp::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::BackUp::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::BackUp::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::BackUp::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::BackUp::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::BackUp::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::BackUp::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathThroughPoses::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathThroughPoses::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathThroughPoses::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathThroughPoses::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathThroughPoses::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathThroughPoses::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathThroughPoses::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathThroughPoses::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathToPose::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathToPose::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathToPose::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathToPose::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathToPose::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathToPose::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathToPose::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::ComputePathToPose::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DriveOnHeading::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DriveOnHeading::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DriveOnHeading::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DriveOnHeading::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DriveOnHeading::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DriveOnHeading::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DriveOnHeading::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DriveOnHeading::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DummyBehavior::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DummyBehavior::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DummyBehavior::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DummyBehavior::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DummyBehavior::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DummyBehavior::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DummyBehavior::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::DummyBehavior::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowPath::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowPath::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowPath::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowPath::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowPath::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowPath::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowPath::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowPath::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowWaypoints::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowWaypoints::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowWaypoints::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowWaypoints::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowWaypoints::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowWaypoints::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowWaypoints::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::FollowWaypoints::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateThroughPoses::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateThroughPoses::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateThroughPoses::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateThroughPoses::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateThroughPoses::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateThroughPoses::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateThroughPoses::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateThroughPoses::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateToPose::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateToPose::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateToPose::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateToPose::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateToPose::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateToPose::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateToPose::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::NavigateToPose::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::SmoothPath::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::SmoothPath::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::SmoothPath::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::SmoothPath::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::SmoothPath::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::SmoothPath::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::SmoothPath::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::SmoothPath::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Spin::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Spin::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Spin::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Spin::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Spin::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Spin::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Spin::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Spin::Result

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Wait::GetResult::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Wait::GetResult::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Wait::SendGoal::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Wait::SendGoal::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Wait::Feedback

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Wait::FeedbackMessage

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Wait::Goal

source§

impl WrappedTypesupport for r2r::nav2_msgs::action::Wait::Result

source§

impl WrappedTypesupport for BehaviorTreeLog

source§

impl WrappedTypesupport for BehaviorTreeStatusChange

source§

impl WrappedTypesupport for CollisionMonitorState

source§

impl WrappedTypesupport for Costmap

source§

impl WrappedTypesupport for CostmapFilterInfo

source§

impl WrappedTypesupport for CostmapMetaData

source§

impl WrappedTypesupport for Particle

source§

impl WrappedTypesupport for ParticleCloud

source§

impl WrappedTypesupport for SpeedLimit

source§

impl WrappedTypesupport for VoxelGrid

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::ClearCostmapAroundRobot::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::ClearCostmapAroundRobot::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::ClearCostmapExceptRegion::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::ClearCostmapExceptRegion::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::ClearEntireCostmap::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::ClearEntireCostmap::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::GetCostmap::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::GetCostmap::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::IsPathValid::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::IsPathValid::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::LoadMap::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::LoadMap::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::ManageLifecycleNodes::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::ManageLifecycleNodes::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::SaveMap::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::SaveMap::Response

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::SetInitialPose::Request

source§

impl WrappedTypesupport for r2r::nav2_msgs::srv::SetInitialPose::Response

source§

impl WrappedTypesupport for GridCells

source§

impl WrappedTypesupport for MapMetaData

source§

impl WrappedTypesupport for OccupancyGrid

source§

impl WrappedTypesupport for Odometry

source§

impl WrappedTypesupport for Path

source§

impl WrappedTypesupport for r2r::nav_msgs::srv::GetMap::Request

source§

impl WrappedTypesupport for r2r::nav_msgs::srv::GetMap::Response

source§

impl WrappedTypesupport for r2r::nav_msgs::srv::GetPlan::Request

source§

impl WrappedTypesupport for r2r::nav_msgs::srv::GetPlan::Response

source§

impl WrappedTypesupport for r2r::nav_msgs::srv::LoadMap::Request

source§

impl WrappedTypesupport for r2r::nav_msgs::srv::LoadMap::Response

source§

impl WrappedTypesupport for r2r::nav_msgs::srv::SetMap::Request

source§

impl WrappedTypesupport for r2r::nav_msgs::srv::SetMap::Response

source§

impl WrappedTypesupport for FloatingPointRange

source§

impl WrappedTypesupport for IntegerRange

source§

impl WrappedTypesupport for ListParametersResult

source§

impl WrappedTypesupport for Log

source§

impl WrappedTypesupport for Parameter

source§

impl WrappedTypesupport for ParameterDescriptor

source§

impl WrappedTypesupport for ParameterEvent

source§

impl WrappedTypesupport for ParameterEventDescriptors

source§

impl WrappedTypesupport for ParameterType

source§

impl WrappedTypesupport for ParameterValue

source§

impl WrappedTypesupport for SetParametersResult

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::DescribeParameters::Request

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::DescribeParameters::Response

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::GetParameterTypes::Request

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::GetParameterTypes::Response

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::GetParameters::Request

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::GetParameters::Response

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::ListParameters::Request

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::ListParameters::Response

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::SetParameters::Request

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::SetParameters::Response

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::SetParametersAtomically::Request

source§

impl WrappedTypesupport for r2r::rcl_interfaces::srv::SetParametersAtomically::Response

source§

impl WrappedTypesupport for Gid

source§

impl WrappedTypesupport for NodeEntitiesInfo

source§

impl WrappedTypesupport for ParticipantEntitiesInfo

source§

impl WrappedTypesupport for Clock

source§

impl WrappedTypesupport for BatteryState

source§

impl WrappedTypesupport for CameraInfo

source§

impl WrappedTypesupport for ChannelFloat32

source§

impl WrappedTypesupport for CompressedImage

source§

impl WrappedTypesupport for FluidPressure

source§

impl WrappedTypesupport for Illuminance

source§

impl WrappedTypesupport for Image

source§

impl WrappedTypesupport for Imu

source§

impl WrappedTypesupport for JointState

source§

impl WrappedTypesupport for Joy

source§

impl WrappedTypesupport for JoyFeedback

source§

impl WrappedTypesupport for JoyFeedbackArray

source§

impl WrappedTypesupport for LaserEcho

source§

impl WrappedTypesupport for LaserScan

source§

impl WrappedTypesupport for MagneticField

source§

impl WrappedTypesupport for MultiDOFJointState

source§

impl WrappedTypesupport for MultiEchoLaserScan

source§

impl WrappedTypesupport for NavSatFix

source§

impl WrappedTypesupport for NavSatStatus

source§

impl WrappedTypesupport for PointCloud2

source§

impl WrappedTypesupport for PointCloud

source§

impl WrappedTypesupport for PointField

source§

impl WrappedTypesupport for Range

source§

impl WrappedTypesupport for RegionOfInterest

source§

impl WrappedTypesupport for RelativeHumidity

source§

impl WrappedTypesupport for Temperature

source§

impl WrappedTypesupport for TimeReference

source§

impl WrappedTypesupport for r2r::sensor_msgs::srv::SetCameraInfo::Request

source§

impl WrappedTypesupport for r2r::sensor_msgs::srv::SetCameraInfo::Response

source§

impl WrappedTypesupport for Mesh

source§

impl WrappedTypesupport for MeshTriangle

source§

impl WrappedTypesupport for Plane

source§

impl WrappedTypesupport for SolidPrimitive

source§

impl WrappedTypesupport for MetricsMessage

source§

impl WrappedTypesupport for StatisticDataPoint

source§

impl WrappedTypesupport for StatisticDataType

source§

impl WrappedTypesupport for Bool

source§

impl WrappedTypesupport for Byte

source§

impl WrappedTypesupport for ByteMultiArray

source§

impl WrappedTypesupport for Char

source§

impl WrappedTypesupport for ColorRGBA

source§

impl WrappedTypesupport for Empty

source§

impl WrappedTypesupport for Float32

source§

impl WrappedTypesupport for Float32MultiArray

source§

impl WrappedTypesupport for Float64

source§

impl WrappedTypesupport for Float64MultiArray

source§

impl WrappedTypesupport for Header

source§

impl WrappedTypesupport for Int8

source§

impl WrappedTypesupport for Int8MultiArray

source§

impl WrappedTypesupport for Int16

source§

impl WrappedTypesupport for Int16MultiArray

source§

impl WrappedTypesupport for Int32

source§

impl WrappedTypesupport for Int32MultiArray

source§

impl WrappedTypesupport for Int64

source§

impl WrappedTypesupport for Int64MultiArray

source§

impl WrappedTypesupport for MultiArrayDimension

source§

impl WrappedTypesupport for MultiArrayLayout

source§

impl WrappedTypesupport for String

source§

impl WrappedTypesupport for UInt8

source§

impl WrappedTypesupport for UInt8MultiArray

source§

impl WrappedTypesupport for UInt16

source§

impl WrappedTypesupport for UInt16MultiArray

source§

impl WrappedTypesupport for UInt32

source§

impl WrappedTypesupport for UInt32MultiArray

source§

impl WrappedTypesupport for UInt64

source§

impl WrappedTypesupport for UInt64MultiArray

source§

impl WrappedTypesupport for r2r::std_srvs::srv::Empty::Request

source§

impl WrappedTypesupport for r2r::std_srvs::srv::Empty::Response

source§

impl WrappedTypesupport for r2r::std_srvs::srv::SetBool::Request

source§

impl WrappedTypesupport for r2r::std_srvs::srv::SetBool::Response

source§

impl WrappedTypesupport for r2r::std_srvs::srv::Trigger::Request

source§

impl WrappedTypesupport for r2r::std_srvs::srv::Trigger::Response

source§

impl WrappedTypesupport for DisparityImage

source§

impl WrappedTypesupport for r2r::tf2_msgs::action::LookupTransform::GetResult::Request

source§

impl WrappedTypesupport for r2r::tf2_msgs::action::LookupTransform::GetResult::Response

source§

impl WrappedTypesupport for r2r::tf2_msgs::action::LookupTransform::SendGoal::Request

source§

impl WrappedTypesupport for r2r::tf2_msgs::action::LookupTransform::SendGoal::Response

source§

impl WrappedTypesupport for r2r::tf2_msgs::action::LookupTransform::Feedback

source§

impl WrappedTypesupport for r2r::tf2_msgs::action::LookupTransform::FeedbackMessage

source§

impl WrappedTypesupport for r2r::tf2_msgs::action::LookupTransform::Goal

source§

impl WrappedTypesupport for r2r::tf2_msgs::action::LookupTransform::Result

source§

impl WrappedTypesupport for TF2Error

source§

impl WrappedTypesupport for TFMessage

source§

impl WrappedTypesupport for r2r::tf2_msgs::srv::FrameGraph::Request

source§

impl WrappedTypesupport for r2r::tf2_msgs::srv::FrameGraph::Response

source§

impl WrappedTypesupport for JointTrajectory

source§

impl WrappedTypesupport for JointTrajectoryPoint

source§

impl WrappedTypesupport for MultiDOFJointTrajectory

source§

impl WrappedTypesupport for MultiDOFJointTrajectoryPoint

source§

impl WrappedTypesupport for UUID

source§

impl WrappedTypesupport for ImageMarker

source§

impl WrappedTypesupport for InteractiveMarker

source§

impl WrappedTypesupport for InteractiveMarkerControl

source§

impl WrappedTypesupport for InteractiveMarkerFeedback

source§

impl WrappedTypesupport for InteractiveMarkerInit

source§

impl WrappedTypesupport for InteractiveMarkerPose

source§

impl WrappedTypesupport for InteractiveMarkerUpdate

source§

impl WrappedTypesupport for Marker

source§

impl WrappedTypesupport for MarkerArray

source§

impl WrappedTypesupport for MenuEntry

source§

impl WrappedTypesupport for MeshFile

source§

impl WrappedTypesupport for UVCoordinate

source§

impl WrappedTypesupport for r2r::visualization_msgs::srv::GetInteractiveMarkers::Request

source§

impl WrappedTypesupport for r2r::visualization_msgs::srv::GetInteractiveMarkers::Response