moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajopt_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, PickNik Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Omid Heidari */
36 #pragma once
37 
38 #include <ros/ros.h>
39 #include <trajopt_sco/sco_common.hpp>
41 #include "problem_description.h"
42 
43 namespace trajopt_interface
44 {
45 MOVEIT_CLASS_FORWARD(TrajOptInterface); // Defines TrajOptInterfacePtr, ConstPtr, WeakPtr... etc
46 
48 {
49 public:
50  TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~"));
51 
52  const sco::BasicTrustRegionSQPParameters& getParams() const
53  {
54  return params_;
55  }
56 
57  bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
58  const planning_interface::MotionPlanRequest& req, moveit_msgs::MotionPlanDetailedResponse& res);
59 
60 protected:
62  void setTrajOptParams(sco::BasicTrustRegionSQPParameters& param);
64  void setProblemInfoParam(ProblemInfo& problem_info);
65  void setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name);
67  const std::vector<std::string>& group_joint_names);
68 
69  ros::NodeHandle nh_;
70  sco::BasicTrustRegionSQPParameters params_;
71  std::vector<sco::Optimizer::Callback> optimizer_callbacks_;
72  TrajOptProblemPtr trajopt_problem_;
73  std::string name_;
74 };
75 
76 void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res);
77 } // namespace trajopt_interface
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)
void setTrajOptParams(sco::BasicTrustRegionSQPParameters &param)
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.
name
Definition: setup.py:7
MOVEIT_CLASS_FORWARD(TermInfo)
void callBackFunc(sco::OptProb *opt_prob, sco::OptResults &opt_res)