30 #ifndef TOWR_INCLUDE_TOWR_ROS_TOWR_ROS_H_ 31 #define TOWR_INCLUDE_TOWR_ROS_TOWR_ROS_H_ 39 #include <xpp_msgs/RobotStateCartesian.h> 40 #include <xpp_msgs/RobotParameters.h> 41 #include <towr_ros/TowrCommand.h> 59 using XppVec = std::vector<xpp::RobotStateCartesian>;
106 const xpp_msgs::RobotParameters& robot_params,
108 bool include_iterations=
false);
110 const std::vector<xpp::RobotStateCartesian>& traj,
111 const std::string& topic)
const;
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)
void PublishInitialState()
XppVec GetTrajectory() const
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.