.. _program_listing_file__tmp_ws_src_pick_ik_include_pick_ik_robot.hpp: Program Listing for File robot.hpp ================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/pick_ik/include/pick_ik/robot.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #pragma once #include #include #include #include #include #include #include namespace pick_ik { struct Robot { struct Variable { double clip_min, clip_max; double span; double min; double max; double max_velocity_rcp; double minimal_displacement_factor; }; std::vector variables; static auto from(std::shared_ptr const& model, moveit::core::JointModelGroup const* jmg, std::vector tip_link_indices) -> Robot; auto get_random_valid_configuration() const -> std::vector; auto is_valid_configuration(std::vector const& config) const -> bool; }; auto get_link_indices(std::shared_ptr const& model, std::vector const& names) -> tl::expected, std::string>; auto get_active_variable_indices(std::shared_ptr const& robot_model, moveit::core::JointModelGroup const* jmg, std::vector const& tip_link_indices) -> std::vector; auto get_minimal_displacement_factors(std::vector const& active_variable_indices, Robot const& robot) -> std::vector; auto get_variables(moveit::core::RobotState const& robot_state) -> std::vector; auto transform_poses_to_frames(moveit::core::RobotState const& robot_state, std::vector const& poses, std::string const& base_frame_name) -> std::vector; } // namespace pick_ik