towr_ros_interface.h
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
30 #ifndef TOWR_INCLUDE_TOWR_ROS_TOWR_ROS_H_
31 #define TOWR_INCLUDE_TOWR_ROS_TOWR_ROS_H_
32 
33 #include <string>
34 
35 #include <ros/ros.h>
36 #include <rosbag/bag.h>
37 
39 #include <xpp_msgs/RobotStateCartesian.h>
40 #include <xpp_msgs/RobotParameters.h>
41 #include <towr_ros/TowrCommand.h>
42 
43 #include <towr/nlp_formulation.h>
44 #include <ifopt/ipopt_solver.h>
45 
46 
47 namespace towr {
48 
49 
58 public:
59  using XppVec = std::vector<xpp::RobotStateCartesian>;
60  using TowrCommandMsg = towr_ros::TowrCommand;
61  using Vector3d = Eigen::Vector3d;
62 
63 protected:
65  virtual ~TowrRosInterface () = default;
66 
70  virtual void SetTowrInitialState() = 0;
71 
79  virtual Parameters GetTowrParameters(int n_ee, const TowrCommandMsg& msg) const = 0;
80 
85  virtual void SetIpoptParameters(const TowrCommandMsg& msg) = 0;
86 
89 
90 private:
94 
98 
99  void UserCommandCallback(const TowrCommandMsg& msg);
100  XppVec GetTrajectory() const;
101  virtual BaseState GetGoalState(const TowrCommandMsg& msg) const;
102  void PublishInitialState();
103  std::vector<XppVec>GetIntermediateSolutions();
104  xpp_msgs::RobotParameters BuildRobotParametersMsg(const RobotModel& model) const;
105  void SaveOptimizationAsRosbag(const std::string& bag_name,
106  const xpp_msgs::RobotParameters& robot_params,
107  const TowrCommandMsg user_command_msg,
108  bool include_iterations=false);
110  const std::vector<xpp::RobotStateCartesian>& traj,
111  const std::string& topic) const;
112 };
113 
114 } /* namespace towr */
115 
116 #endif /* XPP_OPT_INCLUDE_XPP_ROS_OPTIMIZER_NODE_H_ */
std::shared_ptr< IpoptSolver > Ptr
towr_ros::TowrCommand TowrCommandMsg
std::vector< xpp::RobotStateCartesian > XppVec
::ros::Publisher initial_state_pub_
::ros::Subscriber user_command_sub_
double visualization_dt_
duration between two rviz visualization states.
virtual Parameters GetTowrParameters(int n_ee, const TowrCommandMsg &msg) const =0
Formulates the actual TOWR problem to be solved.
ifopt::IpoptSolver::Ptr solver_
NLP solver, could also use SNOPT.
virtual void SetTowrInitialState()=0
Sets the base state and end-effector position.
Base class to interface TOWR with a ROS GUI and RVIZ.
void UserCommandCallback(const TowrCommandMsg &msg)
virtual BaseState GetGoalState(const TowrCommandMsg &msg) const
::ros::Publisher robot_parameters_pub_
SplineHolder solution
the solution splines linked to the opt-variables.
xpp_msgs::RobotParameters BuildRobotParametersMsg(const RobotModel &model) const
ifopt::Problem nlp_
the actual nonlinear program to be solved.
std::vector< XppVec > GetIntermediateSolutions()
void SaveOptimizationAsRosbag(const std::string &bag_name, const xpp_msgs::RobotParameters &robot_params, const TowrCommandMsg user_command_msg, bool include_iterations=false)
void SaveTrajectoryInRosbag(rosbag::Bag &, const std::vector< xpp::RobotStateCartesian > &traj, const std::string &topic) const
virtual ~TowrRosInterface()=default
NlpFormulation formulation_
the default formulation, can be adapted
virtual void SetIpoptParameters(const TowrCommandMsg &msg)=0
Sets the parameters of the nonlinear programming solver IPOPT.


towr_ros
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 2 2021 02:14:21