Public Member Functions | Public Attributes | List of all members
moveit::planning_interface::MoveGroupInterface::Options Struct Reference

Specification of options to use when constructing the MoveGroupInterface class. More...

#include <move_group_interface.h>

Public Member Functions

 Options (std::string group_name, std::string desc=ROBOT_DESCRIPTION, const ros::NodeHandle &node_handle=ros::NodeHandle())
 

Public Attributes

std::string group_name_
 The group to construct the class instance for. More...
 
ros::NodeHandle node_handle_
 
std::string robot_description_
 The robot description parameter name (if different from default) More...
 
moveit::core::RobotModelConstPtr robot_model_
 Optionally, an instance of the RobotModel to use can be also specified. More...
 

Detailed Description

Specification of options to use when constructing the MoveGroupInterface class.

Definition at line 164 of file move_group_interface.h.

Constructor & Destructor Documentation

◆ Options()

moveit::planning_interface::MoveGroupInterface::Options::Options ( std::string  group_name,
std::string  desc = ROBOT_DESCRIPTION,
const ros::NodeHandle node_handle = ros::NodeHandle() 
)
inline

Definition at line 166 of file move_group_interface.h.

Member Data Documentation

◆ group_name_

std::string moveit::planning_interface::MoveGroupInterface::Options::group_name_

The group to construct the class instance for.

Definition at line 173 of file move_group_interface.h.

◆ node_handle_

ros::NodeHandle moveit::planning_interface::MoveGroupInterface::Options::node_handle_

Definition at line 181 of file move_group_interface.h.

◆ robot_description_

std::string moveit::planning_interface::MoveGroupInterface::Options::robot_description_

The robot description parameter name (if different from default)

Definition at line 176 of file move_group_interface.h.

◆ robot_model_

moveit::core::RobotModelConstPtr moveit::planning_interface::MoveGroupInterface::Options::robot_model_

Optionally, an instance of the RobotModel to use can be also specified.

Definition at line 179 of file move_group_interface.h.


The documentation for this struct was generated from the following file:


planning_interface
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:25:17