Base class to interface TOWR with a ROS GUI and RVIZ. More...
#include <towr_ros_interface.h>
Public Types | |
using | TowrCommandMsg = towr_ros::TowrCommand |
using | Vector3d = Eigen::Vector3d |
using | XppVec = std::vector< xpp::RobotStateCartesian > |
Protected Member Functions | |
virtual Parameters | GetTowrParameters (int n_ee, const TowrCommandMsg &msg) const =0 |
Formulates the actual TOWR problem to be solved. More... | |
virtual void | SetIpoptParameters (const TowrCommandMsg &msg)=0 |
Sets the parameters of the nonlinear programming solver IPOPT. More... | |
virtual void | SetTowrInitialState ()=0 |
Sets the base state and end-effector position. More... | |
TowrRosInterface () | |
virtual | ~TowrRosInterface ()=default |
Protected Attributes | |
NlpFormulation | formulation_ |
the default formulation, can be adapted More... | |
ifopt::IpoptSolver::Ptr | solver_ |
NLP solver, could also use SNOPT. More... | |
Private Member Functions | |
xpp_msgs::RobotParameters | BuildRobotParametersMsg (const RobotModel &model) const |
virtual BaseState | GetGoalState (const TowrCommandMsg &msg) const |
std::vector< XppVec > | GetIntermediateSolutions () |
XppVec | GetTrajectory () const |
void | PublishInitialState () |
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 |
void | UserCommandCallback (const TowrCommandMsg &msg) |
Private Attributes | |
::ros::Publisher | initial_state_pub_ |
ifopt::Problem | nlp_ |
the actual nonlinear program to be solved. More... | |
::ros::Publisher | robot_parameters_pub_ |
SplineHolder | solution |
the solution splines linked to the opt-variables. More... | |
::ros::Subscriber | user_command_sub_ |
double | visualization_dt_ |
duration between two rviz visualization states. More... | |
Base class to interface TOWR with a ROS GUI and RVIZ.
This is very convenient to change goal states or terrains on the fly and test how your formulation holds up. A sample application implementing this interface is TowrRosApp.
Definition at line 57 of file towr_ros_interface.h.
using towr::TowrRosInterface::TowrCommandMsg = towr_ros::TowrCommand |
Definition at line 60 of file towr_ros_interface.h.
using towr::TowrRosInterface::Vector3d = Eigen::Vector3d |
Definition at line 61 of file towr_ros_interface.h.
using towr::TowrRosInterface::XppVec = std::vector<xpp::RobotStateCartesian> |
Definition at line 59 of file towr_ros_interface.h.
|
protected |
Definition at line 47 of file towr_ros_interface.cc.
|
protectedvirtualdefault |
|
private |
Definition at line 200 of file towr_ros_interface.cc.
|
privatevirtual |
Definition at line 66 of file towr_ros_interface.cc.
|
private |
Definition at line 152 of file towr_ros_interface.cc.
|
protectedpure virtual |
Formulates the actual TOWR problem to be solved.
msg | User message to adjust the parameters dynamically. |
When formulating your own application, here you can set your specific set of constraints and variables.
Implemented in towr::TowrRosApp.
|
private |
Definition at line 165 of file towr_ros_interface.cc.
|
private |
Definition at line 134 of file towr_ros_interface.cc.
|
private |
Definition at line 220 of file towr_ros_interface.cc.
|
private |
Definition at line 254 of file towr_ros_interface.cc.
|
protectedpure virtual |
Sets the parameters of the nonlinear programming solver IPOPT.
msg | User message that can be used to change the parameters. |
Implemented in towr::TowrRosApp.
|
protectedpure virtual |
Sets the base state and end-effector position.
Implemented in towr::TowrRosApp.
|
private |
Definition at line 78 of file towr_ros_interface.cc.
|
protected |
the default formulation, can be adapted
Definition at line 87 of file towr_ros_interface.h.
|
private |
Definition at line 96 of file towr_ros_interface.h.
|
private |
the actual nonlinear program to be solved.
Definition at line 92 of file towr_ros_interface.h.
|
private |
Definition at line 97 of file towr_ros_interface.h.
|
private |
the solution splines linked to the opt-variables.
Definition at line 91 of file towr_ros_interface.h.
|
protected |
NLP solver, could also use SNOPT.
Definition at line 88 of file towr_ros_interface.h.
|
private |
Definition at line 95 of file towr_ros_interface.h.
|
private |
duration between two rviz visualization states.
Definition at line 93 of file towr_ros_interface.h.