51 double z_ground = 0.0;
54 [&](
Vector3d& p){ p.z() = z_ground; }
72 gait_gen_->SetCombo(id_gait);
73 for (
int ee=0; ee<n_ee; ++ee) {
83 if (msg.optimize_phase_durations)
95 solver_->SetOption(
"linear_solver",
"mumps");
103 solver_->SetOption(
"jacobian_approximation",
"exact");
110 solver_->SetOption(
"max_cpu_time", 40.0);
111 solver_->SetOption(
"print_level", 5);
113 if (msg.play_initialization)
114 solver_->SetOption(
"max_iter", 0);
116 solver_->SetOption(
"max_iter", 3000);
123 int main(
int argc,
char *argv[])
125 ros::init(argc, argv,
"my_towr_ros_app");
Parameters GetTowrParameters(int n_ee, const TowrCommandMsg &msg) const override
Sets the parameters required to formulate the TOWR problem.
towr_ros::TowrCommand TowrCommandMsg
const VectorXd at(Dx deriv) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ifopt::IpoptSolver::Ptr solver_
NLP solver, could also use SNOPT.
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char *argv[])
void SetTowrInitialState() override
Sets the feet to nominal position on flat ground and base above.
Base class to interface TOWR with a ROS GUI and RVIZ.
std::vector< VecTimes > ee_phase_durations_
void OptimizePhaseDurations()
An example application of using TOWR together with ROS.
std::vector< bool > ee_in_contact_at_start_
static Ptr MakeGaitGenerator(int leg_count)
KinematicModel::Ptr kinematic_model_
void SetIpoptParameters(const TowrCommandMsg &msg) override
Sets the paramters for IPOPT.
NlpFormulation formulation_
the default formulation, can be adapted