moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
trajopt_interface::TrajOptInterface Class Reference

#include <trajopt_interface.h>

Public Member Functions

 TrajOptInterface (const ros::NodeHandle &nh=ros::NodeHandle("~"))
 
const sco::BasicTrustRegionSQPParameters & getParams () const
 
bool solve (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MotionPlanDetailedResponse &res)
 

Protected Member Functions

void setTrajOptParams (sco::BasicTrustRegionSQPParameters &param)
 Configure everything using the param server. More...
 
void setDefaultTrajOPtParams ()
 
void setProblemInfoParam (ProblemInfo &problem_info)
 
void setJointPoseTermInfoParams (JointPoseTermInfoPtr &jp, std::string name)
 
trajopt::DblVec extractStartJointValues (const planning_interface::MotionPlanRequest &req, const std::vector< std::string > &group_joint_names)
 

Protected Attributes

ros::NodeHandle nh_
 
sco::BasicTrustRegionSQPParameters params_
 The ROS node handle. More...
 
std::vector< sco::Optimizer::Callback > optimizer_callbacks_
 
TrajOptProblemPtr trajopt_problem_
 
std::string name_
 

Detailed Description

Definition at line 47 of file trajopt_interface.h.

Constructor & Destructor Documentation

◆ TrajOptInterface()

trajopt_interface::TrajOptInterface::TrajOptInterface ( const ros::NodeHandle &  nh = ros::NodeHandle("~"))

Definition at line 61 of file trajopt_interface.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ extractStartJointValues()

trajopt::DblVec trajopt_interface::TrajOptInterface::extractStartJointValues ( const planning_interface::MotionPlanRequest req,
const std::vector< std::string > &  group_joint_names 
)
protected

Definition at line 438 of file trajopt_interface.cpp.

Here is the caller graph for this function:

◆ getParams()

const sco::BasicTrustRegionSQPParameters& trajopt_interface::TrajOptInterface::getParams ( ) const
inline

Definition at line 52 of file trajopt_interface.h.

◆ setDefaultTrajOPtParams()

void trajopt_interface::TrajOptInterface::setDefaultTrajOPtParams ( )
protected

Definition at line 345 of file trajopt_interface.cpp.

Here is the caller graph for this function:

◆ setJointPoseTermInfoParams()

void trajopt_interface::TrajOptInterface::setJointPoseTermInfoParams ( JointPoseTermInfoPtr &  jp,
std::string  name 
)
protected

Definition at line 414 of file trajopt_interface.cpp.

Here is the caller graph for this function:

◆ setProblemInfoParam()

void trajopt_interface::TrajOptInterface::setProblemInfoParam ( ProblemInfo problem_info)
protected

Definition at line 369 of file trajopt_interface.cpp.

Here is the caller graph for this function:

◆ setTrajOptParams()

void trajopt_interface::TrajOptInterface::setTrajOptParams ( sco::BasicTrustRegionSQPParameters &  param)
protected

Configure everything using the param server.

Definition at line 351 of file trajopt_interface.cpp.

Here is the caller graph for this function:

◆ solve()

bool trajopt_interface::TrajOptInterface::solve ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
moveit_msgs::MotionPlanDetailedResponse &  res 
)

Definition at line 70 of file trajopt_interface.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ name_

std::string trajopt_interface::TrajOptInterface::name_
protected

Definition at line 73 of file trajopt_interface.h.

◆ nh_

ros::NodeHandle trajopt_interface::TrajOptInterface::nh_
protected

Definition at line 69 of file trajopt_interface.h.

◆ optimizer_callbacks_

std::vector<sco::Optimizer::Callback> trajopt_interface::TrajOptInterface::optimizer_callbacks_
protected

Definition at line 71 of file trajopt_interface.h.

◆ params_

sco::BasicTrustRegionSQPParameters trajopt_interface::TrajOptInterface::params_
protected

The ROS node handle.

Definition at line 70 of file trajopt_interface.h.

◆ trajopt_problem_

TrajOptProblemPtr trajopt_interface::TrajOptInterface::trajopt_problem_
protected

Definition at line 72 of file trajopt_interface.h.


The documentation for this class was generated from the following files: