#include <trajopt_interface.h>
Definition at line 47 of file trajopt_interface.h.
◆ TrajOptInterface()
trajopt_interface::TrajOptInterface::TrajOptInterface |
( |
const ros::NodeHandle & |
nh = ros::NodeHandle("~") | ) |
|
◆ extractStartJointValues()
◆ getParams()
const sco::BasicTrustRegionSQPParameters& trajopt_interface::TrajOptInterface::getParams |
( |
| ) |
const |
|
inline |
◆ setDefaultTrajOPtParams()
void trajopt_interface::TrajOptInterface::setDefaultTrajOPtParams |
( |
| ) |
|
|
protected |
◆ setJointPoseTermInfoParams()
void trajopt_interface::TrajOptInterface::setJointPoseTermInfoParams |
( |
JointPoseTermInfoPtr & |
jp, |
|
|
std::string |
name |
|
) |
| |
|
protected |
◆ setProblemInfoParam()
void trajopt_interface::TrajOptInterface::setProblemInfoParam |
( |
ProblemInfo & |
problem_info | ) |
|
|
protected |
◆ setTrajOptParams()
void trajopt_interface::TrajOptInterface::setTrajOptParams |
( |
sco::BasicTrustRegionSQPParameters & |
param | ) |
|
|
protected |
◆ solve()
bool trajopt_interface::TrajOptInterface::solve |
( |
const planning_scene::PlanningSceneConstPtr & |
planning_scene, |
|
|
const planning_interface::MotionPlanRequest & |
req, |
|
|
moveit_msgs::MotionPlanDetailedResponse & |
res |
|
) |
| |
◆ name_
std::string trajopt_interface::TrajOptInterface::name_ |
|
protected |
◆ nh_
ros::NodeHandle trajopt_interface::TrajOptInterface::nh_ |
|
protected |
◆ optimizer_callbacks_
std::vector<sco::Optimizer::Callback> trajopt_interface::TrajOptInterface::optimizer_callbacks_ |
|
protected |
◆ params_
sco::BasicTrustRegionSQPParameters trajopt_interface::TrajOptInterface::params_ |
|
protected |
◆ trajopt_problem_
TrajOptProblemPtr trajopt_interface::TrajOptInterface::trajopt_problem_ |
|
protected |
The documentation for this class was generated from the following files: