pick_ik
  • Links
    • Rosindex
  • C++ API
    • Class Hierarchy
    • File Hierarchy
    • Full C++ API
      • Namespaces
        • Namespace kinematics
        • Namespace pick_ik
      • Classes and Structs
        • Struct CachedJointFrames
        • Struct Goal
        • Struct GradientIk
        • Struct GradientIkParams
        • Struct Individual
        • Struct MemeticIkParams
        • Struct Robot
        • Struct Robot::Variable
        • Class MemeticIk
        • Class PickIKPlugin
      • Functions
        • Function pick_ik::get_active_variable_indices
        • Function pick_ik::get_frame(moveit::core::JointModel const&, std::vector<double> const&, std::vector<tf2::Vector3> const&)
        • Function pick_ik::get_frame(moveit::core::LinkModel const&, std::vector<Eigen::Isometry3d> const&)
        • Function pick_ik::get_frame(CachedJointFrames&, moveit::core::JointModel const&, std::vector<double> const&, std::vector<tf2::Vector3> const&)
        • Function pick_ik::get_link_indices
        • Function pick_ik::get_minimal_displacement_factors
        • Function pick_ik::get_variables
        • Function pick_ik::has_joint_moved
        • Function pick_ik::ik_gradient
        • Function pick_ik::ik_memetic
        • Function pick_ik::ik_memetic_impl
        • Function pick_ik::make_avoid_joint_limits_cost_fn
        • Function pick_ik::make_center_joints_cost_fn
        • Function pick_ik::make_cost_fn
        • Function pick_ik::make_fk_fn
        • Function pick_ik::make_frame_tests
        • Function pick_ik::make_ik_cost_fn
        • Function pick_ik::make_is_solution_test_fn
        • Function pick_ik::make_joint_axes
        • Function pick_ik::make_link_frames
        • Function pick_ik::make_minimal_displacement_cost_fn
        • Function pick_ik::make_pose_cost_fn
        • Function pick_ik::make_pose_cost_functions
        • Function pick_ik::step
        • Function pick_ik::transform_poses_to_frames
      • Typedefs
        • Typedef pick_ik::CostFn
        • Typedef pick_ik::FkFn
        • Typedef pick_ik::FrameTestFn
        • Typedef pick_ik::PoseCostFn
        • Typedef pick_ik::SolutionTestFn
      • Directories
        • Directory include
        • Directory pick_ik
      • Files
        • File fk_moveit.hpp
        • File forward_kinematics.hpp
        • File goal.hpp
        • File ik_gradient.hpp
        • File ik_memetic.hpp
        • File pick_ik_plugin.hpp
        • File robot.hpp
  • Standard Documents
    • PACKAGE
    • CHANGELOG
      • Changelog for package pick_ik
        • 1.1.1 (2024-11-30)
        • 1.1.0 (2023-12-13)
        • 1.0.2 (2023-07-25)
        • 1.0.1 (2023-03-28)
        • 1.0.0 (2022-12-08)
    • LICENSE
    • README
      • pick_ik
        • Getting Started
  • Documentation
    • pick_ik : Installation
    • pick_ik : Usage
  • Index
pick_ik
  • C++ API
  • File robot.hpp
  • View page source

File robot.hpp

↰ Parent directory (include/pick_ik)

Contents

  • Definition (include/pick_ik/robot.hpp)

  • Includes

  • Included By

  • Namespaces

  • Classes

  • Functions

Definition (include/pick_ik/robot.hpp)

  • Program Listing for File robot.hpp

Includes

  • Eigen/Geometry

  • moveit/robot_model/joint_model.h

  • moveit/robot_model/joint_model_group.h

  • moveit/robot_model/robot_model.h

  • string

  • tl_expected/expected.hpp

  • vector

Included By

  • File goal.hpp

  • File ik_gradient.hpp

  • File ik_memetic.hpp

  • File pick_ik_plugin.hpp

Namespaces

  • Namespace pick_ik

Classes

  • Struct Robot

  • Struct Robot::Variable

Functions

  • Function pick_ik::get_active_variable_indices

  • Function pick_ik::get_link_indices

  • Function pick_ik::get_minimal_displacement_factors

  • Function pick_ik::get_variables

  • Function pick_ik::transform_poses_to_frames

Previous Next

© Copyright The <pick_ik> Contributors. License: BSD-3-Clause.

Built with Sphinx using a theme provided by Read the Docs.