39 #include <trajopt_sco/sco_common.hpp> 
   52   const sco::BasicTrustRegionSQPParameters& 
getParams()
 const 
   67                                           const std::vector<std::string>& group_joint_names);
 
   70   sco::BasicTrustRegionSQPParameters 
params_;
 
   76 void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res);
 
void setDefaultTrajOPtParams()
 
void setProblemInfoParam(ProblemInfo &problem_info)
 
TrajOptInterface(const ros::NodeHandle &nh=ros::NodeHandle("~"))
 
bool solve(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MotionPlanDetailedResponse &res)
 
sco::BasicTrustRegionSQPParameters params_
The ROS node handle.
 
void setJointPoseTermInfoParams(JointPoseTermInfoPtr &jp, std::string name)
 
TrajOptProblemPtr trajopt_problem_
 
void setTrajOptParams(sco::BasicTrustRegionSQPParameters ¶m)
Configure everything using the param server.
 
trajopt::DblVec extractStartJointValues(const planning_interface::MotionPlanRequest &req, const std::vector< std::string > &group_joint_names)
 
const sco::BasicTrustRegionSQPParameters & getParams() const
 
std::vector< sco::Optimizer::Callback > optimizer_callbacks_
 
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
 
This namespace includes the central class for representing planning contexts.
 
MOVEIT_CLASS_FORWARD(TermInfo)
 
void callBackFunc(sco::OptProb *opt_prob, sco::OptResults &opt_res)