├── .github └── workflows │ ├── build.yaml │ └── doxygen.yaml ├── .gitignore ├── CMakeLists.txt ├── LICENSE ├── README.md ├── bindings └── python │ ├── CMakeLists.txt │ ├── robotoc │ ├── CMakeLists.txt │ ├── __init__.py │ ├── constraints │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── constraint_component_base.cpp │ │ ├── constraints.cpp │ │ ├── contact_wrench_cone.cpp │ │ ├── friction_cone.cpp │ │ ├── impact_constraint_component_base.cpp │ │ ├── impact_friction_cone.cpp │ │ ├── impact_wrench_cone.cpp │ │ ├── joint_acceleration_lower_limit.cpp │ │ ├── joint_acceleration_upper_limit.cpp │ │ ├── joint_position_lower_limit.cpp │ │ ├── joint_position_upper_limit.cpp │ │ ├── joint_torques_lower_limit.cpp │ │ ├── joint_torques_upper_limit.cpp │ │ ├── joint_velocity_lower_limit.cpp │ │ └── joint_velocity_upper_limit.cpp │ ├── core │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── performance_index.cpp │ │ ├── split_direction.cpp │ │ ├── split_kkt_matrix.cpp │ │ ├── split_kkt_residual.cpp │ │ └── split_solution.cpp │ ├── cost │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── com_cost.cpp │ │ ├── com_ref_base.cpp │ │ ├── configuration_space_cost.cpp │ │ ├── configuration_space_ref_base.cpp │ │ ├── cost_function.cpp │ │ ├── cost_function_component_base.cpp │ │ ├── cost_function_data.cpp │ │ ├── discrete_time_com_ref.cpp │ │ ├── discrete_time_swing_foot_ref.cpp │ │ ├── local_contact_force_cost.cpp │ │ ├── periodic_com_ref.cpp │ │ ├── periodic_swing_foot_ref.cpp │ │ ├── task_space_3d_cost.cpp │ │ ├── task_space_3d_ref_base.cpp │ │ ├── task_space_6d_cost.cpp │ │ └── task_space_6d_ref_base.cpp │ ├── line_search │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ └── line_search_settings.cpp │ ├── mpc │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── biped_walk_foot_step_planner.cpp │ │ ├── contact_planner_base.cpp │ │ ├── control_policy.cpp │ │ ├── crawl_foot_step_planner.cpp │ │ ├── flying_trot_foot_step_planner.cpp │ │ ├── jump_foot_step_planner.cpp │ │ ├── mpc_biped_walk.cpp │ │ ├── mpc_crawl.cpp │ │ ├── mpc_flying_trot.cpp │ │ ├── mpc_jump.cpp │ │ ├── mpc_pace.cpp │ │ ├── mpc_periodic_com_ref.cpp │ │ ├── mpc_periodic_configuration_ref.cpp │ │ ├── mpc_periodic_swing_foot_ref.cpp │ │ ├── mpc_trot.cpp │ │ ├── pace_foot_step_planner.cpp │ │ └── trot_foot_step_planner.cpp │ ├── ocp │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── discretization_method.cpp │ │ ├── grid_info.cpp │ │ ├── ocp.cpp │ │ └── time_discretization.cpp │ ├── planner │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── contact_sequence.cpp │ │ └── discrete_event.cpp │ ├── riccati │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── lqr_policy.cpp │ │ └── split_riccati_factorization.cpp │ ├── robot │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── contact_model_info.cpp │ │ ├── contact_status.cpp │ │ ├── impact_status.cpp │ │ ├── robot.cpp │ │ ├── robot_model_info.cpp │ │ ├── robot_properties.cpp │ │ └── se3.cpp │ ├── solver │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── interpolation_order.cpp │ │ ├── ocp_solver.cpp │ │ ├── solver_options.cpp │ │ ├── solver_statistics.cpp │ │ ├── unconstr_ocp_solver.cpp │ │ └── unconstr_parnmpc_solver.cpp │ ├── sto │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── sto_constraints.cpp │ │ ├── sto_cost_function.cpp │ │ └── sto_cost_function_component_base.cpp │ └── utils │ │ ├── CMakeLists.txt │ │ ├── __init__.py │ │ ├── adjust_video_duration.py │ │ ├── benchmark.py │ │ ├── plot.py │ │ ├── rotation.cpp │ │ └── trajectory_viewer.py │ └── robotoc_sim │ ├── CMakeLists.txt │ ├── __init__.py │ ├── legged_simulator.py │ ├── mpc_simulation.py │ └── rsc │ ├── box.urdf │ ├── terrain.obj │ └── terrain.urdf ├── doc ├── .gitignore ├── Doxyfile ├── examples.dox ├── examples │ ├── ocp_solver_cpp.dox │ ├── ocp_solver_py.dox │ ├── ocp_solver_sto_cpp.dox │ ├── ocp_solver_sto_py.dox │ ├── surface_contacts_py.dox │ ├── unconstr_ocp_solver_cpp.dox │ └── unconstr_ocp_solver_py.dox ├── features.dox ├── installation.dox └── mainpage.dox ├── examples ├── README.md ├── a1 │ ├── a1_description │ │ ├── CMakeLists.txt │ │ ├── config │ │ │ └── robot_control.yaml │ │ ├── launch │ │ │ ├── a1_rviz.launch │ │ │ └── check_joint.rviz │ │ ├── meshes │ │ │ ├── calf.dae │ │ │ ├── hip.dae │ │ │ ├── thigh.dae │ │ │ ├── thigh_mirror.dae │ │ │ ├── trunk.dae │ │ │ └── trunk_A1.png │ │ ├── package.xml │ │ ├── urdf │ │ │ └── a1.urdf │ │ └── xacro │ │ │ ├── const.xacro │ │ │ ├── gazebo.xacro │ │ │ ├── leg.xacro │ │ │ ├── materials.xacro │ │ │ ├── robot.xacro │ │ │ ├── stairs.xacro │ │ │ └── transmission.xacro │ ├── mpc │ │ ├── a1_simulator.py │ │ ├── crawl.py │ │ ├── crawl_terrain.py │ │ ├── flying_trot.py │ │ ├── jump.py │ │ ├── pace.py │ │ ├── trot.py │ │ └── trot_terrain.py │ └── python │ │ ├── crawl.py │ │ ├── flying_trot.py │ │ └── trot.py ├── anymal │ ├── CMakeLists.txt │ ├── anymal_b_simple_description │ │ ├── meshes │ │ │ ├── base │ │ │ │ ├── anymal_base.dae │ │ │ │ └── base_uv_texture.jpg │ │ │ ├── foot │ │ │ │ ├── anymal_foot.dae │ │ │ │ └── carbon_uv_texture.jpg │ │ │ ├── hip │ │ │ │ ├── anymal_hip_l.dae │ │ │ │ └── anymal_hip_r.dae │ │ │ ├── shank │ │ │ │ ├── anymal_shank_l.dae │ │ │ │ └── anymal_shank_r.dae │ │ │ └── thigh │ │ │ │ └── anymal_thigh.dae │ │ └── urdf │ │ │ └── anymal.urdf │ ├── bounce.cpp │ ├── crawl.cpp │ ├── jump.cpp │ ├── jump_sto.cpp │ ├── mpc │ │ ├── anymal_simulator.py │ │ ├── crawl.py │ │ └── trot.py │ ├── ocp_benchmark.cpp │ ├── pace.cpp │ ├── python │ │ ├── bounce.py │ │ ├── crawl.py │ │ ├── flying_trot.py │ │ ├── jump.py │ │ ├── jump_sto.py │ │ ├── pace.py │ │ ├── trot.py │ │ ├── trot_sto1.py │ │ └── trot_sto2.py │ ├── run.cpp │ └── trot.cpp ├── anymal_c │ └── mpc │ │ ├── anymal_c_simulator.py │ │ ├── crawl.py │ │ ├── crawl_feedback.py │ │ ├── trot.py │ │ └── trot_feedback.py ├── icub │ ├── icub_description │ │ ├── README.md │ │ ├── meshes │ │ │ └── upmc │ │ │ │ ├── collision │ │ │ │ ├── icub_simple_collision_chest.dae │ │ │ │ ├── icub_simple_collision_head.dae │ │ │ │ ├── icub_simple_collision_l_ankle_1.dae │ │ │ │ ├── icub_simple_collision_l_arm.dae │ │ │ │ ├── icub_simple_collision_l_foot.dae │ │ │ │ ├── icub_simple_collision_l_forearm.dae │ │ │ │ ├── icub_simple_collision_l_hand.dae │ │ │ │ ├── icub_simple_collision_l_hip_1.dae │ │ │ │ ├── icub_simple_collision_l_hip_2.dae │ │ │ │ ├── icub_simple_collision_l_shank.dae │ │ │ │ ├── icub_simple_collision_l_shoulder_1.dae │ │ │ │ ├── icub_simple_collision_l_shoulder_2.dae │ │ │ │ ├── icub_simple_collision_l_thigh.dae │ │ │ │ ├── icub_simple_collision_lap_belt_1.dae │ │ │ │ ├── icub_simple_collision_neck_1.dae │ │ │ │ ├── icub_simple_collision_neck_2.dae │ │ │ │ ├── icub_simple_collision_r_ankle_1.dae │ │ │ │ ├── icub_simple_collision_r_arm.dae │ │ │ │ ├── icub_simple_collision_r_foot.dae │ │ │ │ ├── icub_simple_collision_r_forearm.dae │ │ │ │ ├── icub_simple_collision_r_hand.dae │ │ │ │ ├── icub_simple_collision_r_hip_1.dae │ │ │ │ ├── icub_simple_collision_r_hip_2.dae │ │ │ │ ├── icub_simple_collision_r_shank.dae │ │ │ │ ├── icub_simple_collision_r_shoulder_1.dae │ │ │ │ ├── icub_simple_collision_r_shoulder_2.dae │ │ │ │ ├── icub_simple_collision_r_thigh.dae │ │ │ │ └── icub_simple_collision_root_link.dae │ │ │ │ └── visual │ │ │ │ ├── icub_chest.dae │ │ │ │ ├── icub_head.dae │ │ │ │ ├── icub_l_ankle_1.dae │ │ │ │ ├── icub_l_arm.dae │ │ │ │ ├── icub_l_foot.dae │ │ │ │ ├── icub_l_forearm.dae │ │ │ │ ├── icub_l_hand.dae │ │ │ │ ├── icub_l_hip_1.dae │ │ │ │ ├── icub_l_hip_2.dae │ │ │ │ ├── icub_l_shank.dae │ │ │ │ ├── icub_l_shoulder_1.dae │ │ │ │ ├── icub_l_shoulder_2.dae │ │ │ │ ├── icub_l_thigh.dae │ │ │ │ ├── icub_lap_belt_1.dae │ │ │ │ ├── icub_neck_1.dae │ │ │ │ ├── icub_neck_2.dae │ │ │ │ ├── icub_r_ankle_1.dae │ │ │ │ ├── icub_r_arm.dae │ │ │ │ ├── icub_r_foot.dae │ │ │ │ ├── icub_r_forearm.dae │ │ │ │ ├── icub_r_hand.dae │ │ │ │ ├── icub_r_hip_1.dae │ │ │ │ ├── icub_r_hip_2.dae │ │ │ │ ├── icub_r_shank.dae │ │ │ │ ├── icub_r_shoulder_1.dae │ │ │ │ ├── icub_r_shoulder_2.dae │ │ │ │ ├── icub_r_thigh.dae │ │ │ │ └── icub_root_link.dae │ │ └── urdf │ │ │ ├── icub.urdf │ │ │ └── icub_lower_half.urdf │ ├── mpc │ │ ├── icub_simulator.py │ │ └── walk.py │ └── python │ │ └── jump_sto.py └── iiwa14 │ ├── CMakeLists.txt │ ├── config_space_ocp.cpp │ ├── iiwa_description │ ├── meshes │ │ ├── hokuyo.dae │ │ └── iiwa14 │ │ │ ├── collision │ │ │ ├── link_0.stl │ │ │ ├── link_1.stl │ │ │ ├── link_2.stl │ │ │ ├── link_3.stl │ │ │ ├── link_4.stl │ │ │ ├── link_5.stl │ │ │ ├── link_6.stl │ │ │ └── link_7.stl │ │ │ └── visual │ │ │ ├── link_0.stl │ │ │ ├── link_1.stl │ │ │ ├── link_2.stl │ │ │ ├── link_3.stl │ │ │ ├── link_4.stl │ │ │ ├── link_5.stl │ │ │ ├── link_6.stl │ │ │ └── link_7.stl │ └── urdf │ │ └── iiwa14.urdf │ ├── ocp_benchmark.cpp │ ├── python │ └── config_space_ocp.py │ ├── task_space_ocp.cpp │ ├── unconstr_ocp_benchmark.cpp │ └── unconstr_parnmpc_benchmark.cpp ├── include └── robotoc │ ├── constraints │ ├── constraint_component_base.hpp │ ├── constraint_component_base.hxx │ ├── constraint_component_data.hpp │ ├── constraints.hpp │ ├── constraints_data.hpp │ ├── constraints_data.hxx │ ├── constraints_impl.hpp │ ├── constraints_impl.hxx │ ├── contact_wrench_cone.hpp │ ├── friction_cone.hpp │ ├── impact_constraint_component_base.hpp │ ├── impact_constraint_component_base.hxx │ ├── impact_friction_cone.hpp │ ├── impact_wrench_cone.hpp │ ├── joint_acceleration_lower_limit.hpp │ ├── joint_acceleration_upper_limit.hpp │ ├── joint_position_lower_limit.hpp │ ├── joint_position_upper_limit.hpp │ ├── joint_torques_lower_limit.hpp │ ├── joint_torques_upper_limit.hpp │ ├── joint_velocity_lower_limit.hpp │ ├── joint_velocity_upper_limit.hpp │ ├── pdipm.hpp │ └── pdipm.hxx │ ├── core │ ├── direction.hpp │ ├── kkt_matrix.hpp │ ├── kkt_residual.hpp │ ├── performance_index.hpp │ ├── solution.hpp │ ├── split_direction.hpp │ ├── split_direction.hxx │ ├── split_kkt_matrix.hpp │ ├── split_kkt_matrix.hxx │ ├── split_kkt_residual.hpp │ ├── split_kkt_residual.hxx │ ├── split_solution.hpp │ └── split_solution.hxx │ ├── cost │ ├── com_cost.hpp │ ├── com_ref_base.hpp │ ├── configuration_space_cost.hpp │ ├── configuration_space_ref_base.hpp │ ├── cost_function.hpp │ ├── cost_function_component_base.hpp │ ├── cost_function_data.hpp │ ├── discrete_time_com_ref.hpp │ ├── discrete_time_swing_foot_ref.hpp │ ├── foot_trajectory_type.hpp │ ├── local_contact_force_cost.hpp │ ├── periodic_com_ref.hpp │ ├── periodic_swing_foot_ref.hpp │ ├── task_space_3d_cost.hpp │ ├── task_space_3d_ref_base.hpp │ ├── task_space_6d_cost.hpp │ ├── task_space_6d_ref_base.hpp │ └── trot_swing_foot_ref.hpp │ ├── dynamics │ ├── contact_dynamics.hpp │ ├── contact_dynamics_data.hpp │ ├── contact_dynamics_data.hxx │ ├── impact_dynamics.hpp │ ├── impact_state_equation.hpp │ ├── state_equation.hpp │ ├── state_equation_data.hpp │ ├── switching_constraint.hpp │ ├── switching_constraint_data.hpp │ ├── terminal_state_equation.hpp │ ├── unconstr_dynamics.hpp │ └── unconstr_state_equation.hpp │ ├── line_search │ ├── line_search.hpp │ ├── line_search_filter.hpp │ ├── line_search_settings.hpp │ └── unconstr_line_search.hpp │ ├── mpc │ ├── biped_walk_foot_step_planner.hpp │ ├── contact_planner_base.hpp │ ├── control_policy.hpp │ ├── crawl_foot_step_planner.hpp │ ├── flying_trot_foot_step_planner.hpp │ ├── jump_foot_step_planner.hpp │ ├── moving_window_filter.hpp │ ├── mpc_biped_walk.hpp │ ├── mpc_crawl.hpp │ ├── mpc_flying_trot.hpp │ ├── mpc_jump.hpp │ ├── mpc_pace.hpp │ ├── mpc_periodic_com_ref.hpp │ ├── mpc_periodic_configuration_ref.hpp │ ├── mpc_periodic_swing_foot_ref.hpp │ ├── mpc_trot.hpp │ ├── pace_foot_step_planner.hpp │ ├── raibert_heuristic.hpp │ └── trot_foot_step_planner.hpp │ ├── ocp │ ├── direct_multiple_shooting.hpp │ ├── discretization_method.hpp │ ├── grid_info.hpp │ ├── impact_stage.hpp │ ├── intermediate_stage.hpp │ ├── ocp.hpp │ ├── ocp_data.hpp │ ├── terminal_stage.hpp │ └── time_discretization.hpp │ ├── parnmpc │ ├── unconstr_backward_correction.hpp │ ├── unconstr_kkt_matrix_inverter.hpp │ ├── unconstr_kkt_matrix_inverter.hxx │ └── unconstr_split_backward_correction.hpp │ ├── planner │ ├── contact_sequence.hpp │ └── discrete_event.hpp │ ├── riccati │ ├── backward_riccati_recursion_factorizer.hpp │ ├── lqr_policy.hpp │ ├── riccati_factorization.hpp │ ├── riccati_factorizer.hpp │ ├── riccati_recursion.hpp │ ├── split_constrained_riccati_factorization.hpp │ ├── split_constrained_riccati_factorization.hxx │ ├── split_riccati_factorization.hpp │ ├── split_riccati_factorization.hxx │ ├── sto_policy.hpp │ ├── unconstr_backward_riccati_recursion_factorizer.hpp │ ├── unconstr_riccati_factorizer.hpp │ └── unconstr_riccati_recursion.hpp │ ├── robot │ ├── contact_model_info.hpp │ ├── contact_status.hpp │ ├── contact_status.hxx │ ├── impact_status.hpp │ ├── impact_status.hxx │ ├── point_contact.hpp │ ├── point_contact.hxx │ ├── robot.hpp │ ├── robot.hxx │ ├── robot_model_info.hpp │ ├── robot_properties.hpp │ ├── se3.hpp │ ├── se3_jacobian_inverse.hpp │ ├── se3_jacobian_inverse.hxx │ ├── surface_contact.hpp │ └── surface_contact.hxx │ ├── solver │ ├── interpolation_order.hpp │ ├── ocp_solver.hpp │ ├── solution_interpolator.hpp │ ├── solver_options.hpp │ ├── solver_statistics.hpp │ ├── unconstr_ocp_solver.hpp │ └── unconstr_parnmpc_solver.hpp │ ├── sto │ ├── sto_constraints.hpp │ ├── sto_cost_function.hpp │ ├── sto_cost_function_component_base.hpp │ └── switching_time_optimization.hpp │ ├── unconstr │ ├── parnmpc_intermediate_stage.hpp │ ├── parnmpc_terminal_stage.hpp │ ├── unconstr_direct_multiple_shooting.hpp │ ├── unconstr_intermediate_stage.hpp │ ├── unconstr_ocp_data.hpp │ └── unconstr_terminal_stage.hpp │ └── utils │ ├── aligned_deque.hpp │ ├── aligned_unordered_map.hpp │ ├── aligned_vector.hpp │ ├── derivative_checker.hpp │ ├── numerics.hpp │ ├── ocp_benchmarker.hpp │ ├── ocp_benchmarker.hxx │ ├── pybind11_macros.hpp │ ├── rotation.hpp │ └── timer.hpp ├── requirements.txt ├── src ├── constraints │ ├── constraint_component_base.cpp │ ├── constraint_component_data.cpp │ ├── constraints.cpp │ ├── constraints_data.cpp │ ├── contact_wrench_cone.cpp │ ├── friction_cone.cpp │ ├── impact_constraint_component_base.cpp │ ├── impact_friction_cone.cpp │ ├── impact_wrench_cone.cpp │ ├── joint_acceleration_lower_limit.cpp │ ├── joint_acceleration_upper_limit.cpp │ ├── joint_position_lower_limit.cpp │ ├── joint_position_upper_limit.cpp │ ├── joint_torques_lower_limit.cpp │ ├── joint_torques_upper_limit.cpp │ ├── joint_velocity_lower_limit.cpp │ └── joint_velocity_upper_limit.cpp ├── core │ ├── direction.cpp │ ├── kkt_matrix.cpp │ ├── kkt_residual.cpp │ ├── performance_index.cpp │ ├── solution.cpp │ ├── split_direction.cpp │ ├── split_kkt_matrix.cpp │ ├── split_kkt_residual.cpp │ └── split_solution.cpp ├── cost │ ├── com_cost.cpp │ ├── configuration_space_cost.cpp │ ├── cost_function.cpp │ ├── cost_function_data.cpp │ ├── discrete_time_com_ref.cpp │ ├── discrete_time_swing_foot_ref.cpp │ ├── local_contact_force_cost.cpp │ ├── periodic_com_ref.cpp │ ├── periodic_swing_foot_ref.cpp │ ├── task_space_3d_cost.cpp │ └── task_space_6d_cost.cpp ├── dynamics │ ├── contact_dynamics.cpp │ ├── contact_dynamics_data.cpp │ ├── impact_dynamics.cpp │ ├── impact_state_equation.cpp │ ├── state_equation.cpp │ ├── state_equation_data.cpp │ ├── switching_constraint.cpp │ ├── switching_constraint_data.cpp │ ├── terminal_state_equation.cpp │ ├── unconstr_dynamics.cpp │ └── unconstr_state_equation.cpp ├── line_search │ ├── line_search.cpp │ ├── line_search_filter.cpp │ ├── line_search_settings.cpp │ └── unconstr_line_search.cpp ├── mpc │ ├── biped_walk_foot_step_planner.cpp │ ├── contact_planner_base.cpp │ ├── control_policy.cpp │ ├── crawl_foot_step_planner.cpp │ ├── flying_trot_foot_step_planner.cpp │ ├── jump_foot_step_planner.cpp │ ├── mpc_biped_walk.cpp │ ├── mpc_crawl.cpp │ ├── mpc_flying_trot.cpp │ ├── mpc_jump.cpp │ ├── mpc_pace.cpp │ ├── mpc_periodic_com_ref.cpp │ ├── mpc_periodic_configuration_ref.cpp │ ├── mpc_periodic_swing_foot_ref.cpp │ ├── mpc_trot.cpp │ ├── pace_foot_step_planner.cpp │ ├── raibert_heuristic.cpp │ └── trot_foot_step_planner.cpp ├── ocp │ ├── direct_multiple_shooting.cpp │ ├── grid_info.cpp │ ├── impact_stage.cpp │ ├── intermediate_stage.cpp │ ├── ocp.cpp │ ├── terminal_stage.cpp │ └── time_discretization.cpp ├── parnmpc │ ├── unconstr_backward_correction.cpp │ └── unconstr_split_backward_correction.cpp ├── planner │ ├── contact_sequence.cpp │ └── discrete_event.cpp ├── riccati │ ├── backward_riccati_recursion_factorizer.cpp │ ├── riccati_factorization.cpp │ ├── riccati_factorizer.cpp │ ├── riccati_recursion.cpp │ ├── split_constrained_riccati_factorization.cpp │ ├── split_riccati_factorization.cpp │ ├── unconstr_backward_riccati_recursion_factorizer.cpp │ ├── unconstr_riccati_factorizer.cpp │ └── unconstr_riccati_recursion.cpp ├── robot │ ├── contact_model_info.cpp │ ├── contact_status.cpp │ ├── impact_status.cpp │ ├── point_contact.cpp │ ├── robot.cpp │ ├── robot_model_info.cpp │ └── surface_contact.cpp ├── solver │ ├── ocp_solver.cpp │ ├── solution_interpolator.cpp │ ├── solver_options.cpp │ ├── solver_statistics.cpp │ ├── unconstr_ocp_solver.cpp │ └── unconstr_parnmpc_solver.cpp ├── sto │ ├── sto_constraints.cpp │ ├── sto_cost_function.cpp │ └── switching_time_optimization.cpp ├── unconstr │ ├── parnmpc_intermediate_stage.cpp │ ├── parnmpc_terminal_stage.cpp │ ├── unconstr_direct_multiple_shooting.cpp │ ├── unconstr_intermediate_stage.cpp │ └── unconstr_terminal_stage.cpp └── utils │ └── derivative_checker.cpp └── test ├── CMakeLists.txt ├── cmake └── gtest.cmake ├── constraints ├── CMakeLists.txt ├── constraint_component_data_test.cpp ├── constraints_data_test.cpp ├── constraints_test.cpp ├── contact_wrench_cone_test.cpp ├── friction_cone_test.cpp ├── impact_friction_cone_test.cpp ├── impact_wrench_cone_test.cpp ├── joint_acceleration_lower_limit_test.cpp ├── joint_acceleration_upper_limit_test.cpp ├── joint_position_lower_limit_test.cpp ├── joint_position_upper_limit_test.cpp ├── joint_torques_lower_limit_test.cpp ├── joint_torques_upper_limit_test.cpp ├── joint_velocity_lower_limit_test.cpp ├── joint_velocity_upper_limit_test.cpp └── pdipm_test.cpp ├── core ├── CMakeLists.txt ├── split_direction_test.cpp ├── split_kkt_matrix_test.cpp ├── split_kkt_residual_test.cpp └── split_solution_test.cpp ├── cost ├── CMakeLists.txt ├── com_cost_test.cpp ├── configuration_space_cost_test.cpp ├── cost_function_test.cpp ├── discrete_time_com_ref.cpp ├── discrete_time_swing_foot_ref_test.cpp ├── local_contact_force_cost_test.cpp ├── periodic_com_ref_test.cpp ├── periodic_swing_foot_ref_test.cpp ├── task_space_3d_cost_test.cpp └── task_space_6d_cost_test.cpp ├── dynamics ├── CMakeLists.txt ├── contact_dynamics_data_test.cpp ├── contact_dynamics_test.cpp ├── impact_dynamics_test.cpp ├── impact_state_equation_test.cpp ├── state_equation_test.cpp ├── switching_constraint_test.cpp ├── terminal_state_equation_test.cpp └── unconstr_dynamics_test.cpp ├── line_search ├── CMakeLists.txt ├── line_search_filter_test.cpp ├── line_search_test.cpp └── unconstr_line_search_test.cpp ├── mpc ├── CMakeLists.txt ├── biped_walk_foot_step_planner_test.cpp ├── crawl_foot_step_planner_test.cpp ├── flying_trot_foot_step_planner_test.cpp ├── jump_foot_step_planner_test.cpp ├── moving_window_filter_test.cpp ├── pace_foot_step_planner_test.cpp ├── raibert_heuristic_test.cpp └── trot_foot_step_planner_test.cpp ├── ocp ├── CMakeLists.txt ├── direct_multiple_shooting_test.cpp ├── impact_stage_test.cpp ├── intermediate_stage_test.cpp ├── terminal_stage_test.cpp └── time_discretization_test.cpp ├── parnmpc ├── CMakeLists.txt ├── unconstr_kkt_matrix_inverter_test.cpp └── unconstr_split_backward_correction_test.cpp ├── planner ├── CMakeLists.txt ├── contact_sequence_test.cpp └── discrete_event_test.cpp ├── riccati ├── CMakeLists.txt ├── backward_riccati_recursion_factorizer_test.cpp ├── riccati_factorizer_test.cpp ├── riccati_recursion_test.cpp ├── split_riccati_factorization_test.cpp ├── unconstr_backward_riccati_recursion_factorizer_test.cpp ├── unconstr_riccati_factorizer_test.cpp └── unconstr_riccati_recursion_test.cpp ├── robot ├── CMakeLists.txt ├── contact_status_test.cpp ├── impact_status_test.cpp ├── point_contact_test.cpp ├── robot_test.cpp ├── se3_jacobian_inverse_test.cpp └── surface_contact_test.cpp ├── solver ├── CMakeLists.txt ├── ocp_solver_test.cpp ├── solver_options_test.cpp ├── solver_statistics_test.cpp ├── unconstr_ocp_solver_test.cpp └── unconstr_parnmpc_solver_test.cpp ├── sto ├── CMakeLists.txt ├── sto_constraints_test.cpp └── sto_cost_function_test.cpp ├── test_helper ├── CMakeLists.txt ├── constraints_factory.cpp ├── constraints_factory.hpp ├── contact_sequence_factory.cpp ├── contact_sequence_factory.hpp ├── contact_status_factory.cpp ├── contact_status_factory.hpp ├── cost_factory.cpp ├── cost_factory.hpp ├── direction_factory.cpp ├── direction_factory.hpp ├── kkt_factory.cpp ├── kkt_factory.hpp ├── riccati_factory.cpp ├── riccati_factory.hpp ├── robot_factory.cpp ├── robot_factory.hpp ├── solution_factory.cpp ├── solution_factory.hpp ├── test_helper.hpp ├── urdf_factory.cpp └── urdf_factory.hpp ├── unconstr ├── CMakeLists.txt ├── parnmpc_intermediate_stage_test.cpp ├── parnmpc_terminal_stage_test.cpp ├── unconstr_intermediate_stage_test.cpp └── unconstr_terminal_stage_test.cpp └── urdf ├── anymal └── anymal.urdf ├── icub └── icub.urdf └── iiwa14 └── iiwa14.urdf /.github/workflows/build.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/.github/workflows/build.yaml -------------------------------------------------------------------------------- /.github/workflows/doxygen.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/.github/workflows/doxygen.yaml -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/.gitignore -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/CMakeLists.txt -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/LICENSE -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/README.md -------------------------------------------------------------------------------- /bindings/python/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/constraint_component_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/constraint_component_base.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/constraints.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/constraints.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/contact_wrench_cone.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/contact_wrench_cone.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/friction_cone.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/friction_cone.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/impact_constraint_component_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/impact_constraint_component_base.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/impact_friction_cone.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/impact_friction_cone.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/impact_wrench_cone.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/impact_wrench_cone.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/joint_acceleration_lower_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/joint_acceleration_lower_limit.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/joint_acceleration_upper_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/joint_acceleration_upper_limit.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/joint_position_lower_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/joint_position_lower_limit.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/joint_position_upper_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/joint_position_upper_limit.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/joint_torques_lower_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/joint_torques_lower_limit.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/joint_torques_upper_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/joint_torques_upper_limit.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/joint_velocity_lower_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/joint_velocity_lower_limit.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/constraints/joint_velocity_upper_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/constraints/joint_velocity_upper_limit.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/core/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/core/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/core/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/core/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/core/performance_index.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/core/performance_index.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/core/split_direction.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/core/split_direction.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/core/split_kkt_matrix.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/core/split_kkt_matrix.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/core/split_kkt_residual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/core/split_kkt_residual.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/core/split_solution.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/core/split_solution.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/com_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/com_cost.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/com_ref_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/com_ref_base.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/configuration_space_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/configuration_space_cost.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/configuration_space_ref_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/configuration_space_ref_base.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/cost_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/cost_function.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/cost_function_component_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/cost_function_component_base.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/cost_function_data.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/cost_function_data.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/discrete_time_com_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/discrete_time_com_ref.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/discrete_time_swing_foot_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/discrete_time_swing_foot_ref.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/local_contact_force_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/local_contact_force_cost.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/periodic_com_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/periodic_com_ref.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/periodic_swing_foot_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/periodic_swing_foot_ref.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/task_space_3d_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/task_space_3d_cost.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/task_space_3d_ref_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/task_space_3d_ref_base.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/task_space_6d_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/task_space_6d_cost.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/cost/task_space_6d_ref_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/cost/task_space_6d_ref_base.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/line_search/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/line_search/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/line_search/__init__.py: -------------------------------------------------------------------------------- 1 | from .line_search_settings import * -------------------------------------------------------------------------------- /bindings/python/robotoc/line_search/line_search_settings.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/line_search/line_search_settings.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/biped_walk_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/biped_walk_foot_step_planner.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/contact_planner_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/contact_planner_base.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/control_policy.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/control_policy.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/crawl_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/crawl_foot_step_planner.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/flying_trot_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/flying_trot_foot_step_planner.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/jump_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/jump_foot_step_planner.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/mpc_biped_walk.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/mpc_biped_walk.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/mpc_crawl.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/mpc_crawl.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/mpc_flying_trot.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/mpc_flying_trot.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/mpc_jump.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/mpc_jump.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/mpc_pace.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/mpc_pace.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/mpc_periodic_com_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/mpc_periodic_com_ref.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/mpc_periodic_configuration_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/mpc_periodic_configuration_ref.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/mpc_periodic_swing_foot_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/mpc_periodic_swing_foot_ref.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/mpc_trot.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/mpc_trot.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/pace_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/pace_foot_step_planner.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/mpc/trot_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/mpc/trot_foot_step_planner.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/ocp/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/ocp/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/ocp/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/ocp/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/ocp/discretization_method.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/ocp/discretization_method.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/ocp/grid_info.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/ocp/grid_info.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/ocp/ocp.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/ocp/ocp.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/ocp/time_discretization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/ocp/time_discretization.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/planner/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/planner/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/planner/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/planner/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/planner/contact_sequence.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/planner/contact_sequence.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/planner/discrete_event.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/planner/discrete_event.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/riccati/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/riccati/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/riccati/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/riccati/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/riccati/lqr_policy.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/riccati/lqr_policy.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/riccati/split_riccati_factorization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/riccati/split_riccati_factorization.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/robot/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/robot/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/robot/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/robot/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/robot/contact_model_info.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/robot/contact_model_info.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/robot/contact_status.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/robot/contact_status.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/robot/impact_status.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/robot/impact_status.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/robot/robot.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/robot/robot.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/robot/robot_model_info.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/robot/robot_model_info.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/robot/robot_properties.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/robot/robot_properties.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/robot/se3.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/robot/se3.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/solver/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/solver/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/solver/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/solver/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/solver/interpolation_order.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/solver/interpolation_order.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/solver/ocp_solver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/solver/ocp_solver.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/solver/solver_options.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/solver/solver_options.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/solver/solver_statistics.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/solver/solver_statistics.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/solver/unconstr_ocp_solver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/solver/unconstr_ocp_solver.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/solver/unconstr_parnmpc_solver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/solver/unconstr_parnmpc_solver.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/sto/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/sto/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/sto/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/sto/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/sto/sto_constraints.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/sto/sto_constraints.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/sto/sto_cost_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/sto/sto_cost_function.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/sto/sto_cost_function_component_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/sto/sto_cost_function_component_base.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/utils/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/utils/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc/utils/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/utils/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc/utils/adjust_video_duration.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/utils/adjust_video_duration.py -------------------------------------------------------------------------------- /bindings/python/robotoc/utils/benchmark.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/utils/benchmark.py -------------------------------------------------------------------------------- /bindings/python/robotoc/utils/plot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/utils/plot.py -------------------------------------------------------------------------------- /bindings/python/robotoc/utils/rotation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/utils/rotation.cpp -------------------------------------------------------------------------------- /bindings/python/robotoc/utils/trajectory_viewer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc/utils/trajectory_viewer.py -------------------------------------------------------------------------------- /bindings/python/robotoc_sim/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc_sim/CMakeLists.txt -------------------------------------------------------------------------------- /bindings/python/robotoc_sim/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc_sim/__init__.py -------------------------------------------------------------------------------- /bindings/python/robotoc_sim/legged_simulator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc_sim/legged_simulator.py -------------------------------------------------------------------------------- /bindings/python/robotoc_sim/mpc_simulation.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc_sim/mpc_simulation.py -------------------------------------------------------------------------------- /bindings/python/robotoc_sim/rsc/box.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc_sim/rsc/box.urdf -------------------------------------------------------------------------------- /bindings/python/robotoc_sim/rsc/terrain.obj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc_sim/rsc/terrain.obj -------------------------------------------------------------------------------- /bindings/python/robotoc_sim/rsc/terrain.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/bindings/python/robotoc_sim/rsc/terrain.urdf -------------------------------------------------------------------------------- /doc/.gitignore: -------------------------------------------------------------------------------- 1 | html 2 | latex 3 | man -------------------------------------------------------------------------------- /doc/Doxyfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/Doxyfile -------------------------------------------------------------------------------- /doc/examples.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/examples.dox -------------------------------------------------------------------------------- /doc/examples/ocp_solver_cpp.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/examples/ocp_solver_cpp.dox -------------------------------------------------------------------------------- /doc/examples/ocp_solver_py.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/examples/ocp_solver_py.dox -------------------------------------------------------------------------------- /doc/examples/ocp_solver_sto_cpp.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/examples/ocp_solver_sto_cpp.dox -------------------------------------------------------------------------------- /doc/examples/ocp_solver_sto_py.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/examples/ocp_solver_sto_py.dox -------------------------------------------------------------------------------- /doc/examples/surface_contacts_py.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/examples/surface_contacts_py.dox -------------------------------------------------------------------------------- /doc/examples/unconstr_ocp_solver_cpp.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/examples/unconstr_ocp_solver_cpp.dox -------------------------------------------------------------------------------- /doc/examples/unconstr_ocp_solver_py.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/examples/unconstr_ocp_solver_py.dox -------------------------------------------------------------------------------- /doc/features.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/features.dox -------------------------------------------------------------------------------- /doc/installation.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/installation.dox -------------------------------------------------------------------------------- /doc/mainpage.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/doc/mainpage.dox -------------------------------------------------------------------------------- /examples/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/README.md -------------------------------------------------------------------------------- /examples/a1/a1_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/CMakeLists.txt -------------------------------------------------------------------------------- /examples/a1/a1_description/config/robot_control.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/config/robot_control.yaml -------------------------------------------------------------------------------- /examples/a1/a1_description/launch/a1_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/launch/a1_rviz.launch -------------------------------------------------------------------------------- /examples/a1/a1_description/launch/check_joint.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/launch/check_joint.rviz -------------------------------------------------------------------------------- /examples/a1/a1_description/meshes/calf.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/meshes/calf.dae -------------------------------------------------------------------------------- /examples/a1/a1_description/meshes/hip.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/meshes/hip.dae -------------------------------------------------------------------------------- /examples/a1/a1_description/meshes/thigh.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/meshes/thigh.dae -------------------------------------------------------------------------------- /examples/a1/a1_description/meshes/thigh_mirror.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/meshes/thigh_mirror.dae -------------------------------------------------------------------------------- /examples/a1/a1_description/meshes/trunk.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/meshes/trunk.dae -------------------------------------------------------------------------------- /examples/a1/a1_description/meshes/trunk_A1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/meshes/trunk_A1.png -------------------------------------------------------------------------------- /examples/a1/a1_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/package.xml -------------------------------------------------------------------------------- /examples/a1/a1_description/urdf/a1.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/urdf/a1.urdf -------------------------------------------------------------------------------- /examples/a1/a1_description/xacro/const.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/xacro/const.xacro -------------------------------------------------------------------------------- /examples/a1/a1_description/xacro/gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/xacro/gazebo.xacro -------------------------------------------------------------------------------- /examples/a1/a1_description/xacro/leg.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/xacro/leg.xacro -------------------------------------------------------------------------------- /examples/a1/a1_description/xacro/materials.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/xacro/materials.xacro -------------------------------------------------------------------------------- /examples/a1/a1_description/xacro/robot.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/xacro/robot.xacro -------------------------------------------------------------------------------- /examples/a1/a1_description/xacro/stairs.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/xacro/stairs.xacro -------------------------------------------------------------------------------- /examples/a1/a1_description/xacro/transmission.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/a1_description/xacro/transmission.xacro -------------------------------------------------------------------------------- /examples/a1/mpc/a1_simulator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/mpc/a1_simulator.py -------------------------------------------------------------------------------- /examples/a1/mpc/crawl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/mpc/crawl.py -------------------------------------------------------------------------------- /examples/a1/mpc/crawl_terrain.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/mpc/crawl_terrain.py -------------------------------------------------------------------------------- /examples/a1/mpc/flying_trot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/mpc/flying_trot.py -------------------------------------------------------------------------------- /examples/a1/mpc/jump.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/mpc/jump.py -------------------------------------------------------------------------------- /examples/a1/mpc/pace.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/mpc/pace.py -------------------------------------------------------------------------------- /examples/a1/mpc/trot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/mpc/trot.py -------------------------------------------------------------------------------- /examples/a1/mpc/trot_terrain.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/mpc/trot_terrain.py -------------------------------------------------------------------------------- /examples/a1/python/crawl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/python/crawl.py -------------------------------------------------------------------------------- /examples/a1/python/flying_trot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/python/flying_trot.py -------------------------------------------------------------------------------- /examples/a1/python/trot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/a1/python/trot.py -------------------------------------------------------------------------------- /examples/anymal/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/CMakeLists.txt -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/meshes/base/anymal_base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/meshes/base/anymal_base.dae -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/meshes/base/base_uv_texture.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/meshes/base/base_uv_texture.jpg -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/meshes/foot/anymal_foot.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/meshes/foot/anymal_foot.dae -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/meshes/foot/carbon_uv_texture.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/meshes/foot/carbon_uv_texture.jpg -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/meshes/hip/anymal_hip_l.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/meshes/hip/anymal_hip_l.dae -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/meshes/hip/anymal_hip_r.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/meshes/hip/anymal_hip_r.dae -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/meshes/shank/anymal_shank_l.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/meshes/shank/anymal_shank_l.dae -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/meshes/shank/anymal_shank_r.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/meshes/shank/anymal_shank_r.dae -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/meshes/thigh/anymal_thigh.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/meshes/thigh/anymal_thigh.dae -------------------------------------------------------------------------------- /examples/anymal/anymal_b_simple_description/urdf/anymal.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/anymal_b_simple_description/urdf/anymal.urdf -------------------------------------------------------------------------------- /examples/anymal/bounce.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/bounce.cpp -------------------------------------------------------------------------------- /examples/anymal/crawl.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/crawl.cpp -------------------------------------------------------------------------------- /examples/anymal/jump.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/jump.cpp -------------------------------------------------------------------------------- /examples/anymal/jump_sto.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/jump_sto.cpp -------------------------------------------------------------------------------- /examples/anymal/mpc/anymal_simulator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/mpc/anymal_simulator.py -------------------------------------------------------------------------------- /examples/anymal/mpc/crawl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/mpc/crawl.py -------------------------------------------------------------------------------- /examples/anymal/mpc/trot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/mpc/trot.py -------------------------------------------------------------------------------- /examples/anymal/ocp_benchmark.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/ocp_benchmark.cpp -------------------------------------------------------------------------------- /examples/anymal/pace.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/pace.cpp -------------------------------------------------------------------------------- /examples/anymal/python/bounce.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/python/bounce.py -------------------------------------------------------------------------------- /examples/anymal/python/crawl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/python/crawl.py -------------------------------------------------------------------------------- /examples/anymal/python/flying_trot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/python/flying_trot.py -------------------------------------------------------------------------------- /examples/anymal/python/jump.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/python/jump.py -------------------------------------------------------------------------------- /examples/anymal/python/jump_sto.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/python/jump_sto.py -------------------------------------------------------------------------------- /examples/anymal/python/pace.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/python/pace.py -------------------------------------------------------------------------------- /examples/anymal/python/trot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/python/trot.py -------------------------------------------------------------------------------- /examples/anymal/python/trot_sto1.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/python/trot_sto1.py -------------------------------------------------------------------------------- /examples/anymal/python/trot_sto2.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/python/trot_sto2.py -------------------------------------------------------------------------------- /examples/anymal/run.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/run.cpp -------------------------------------------------------------------------------- /examples/anymal/trot.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal/trot.cpp -------------------------------------------------------------------------------- /examples/anymal_c/mpc/anymal_c_simulator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal_c/mpc/anymal_c_simulator.py -------------------------------------------------------------------------------- /examples/anymal_c/mpc/crawl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal_c/mpc/crawl.py -------------------------------------------------------------------------------- /examples/anymal_c/mpc/crawl_feedback.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal_c/mpc/crawl_feedback.py -------------------------------------------------------------------------------- /examples/anymal_c/mpc/trot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal_c/mpc/trot.py -------------------------------------------------------------------------------- /examples/anymal_c/mpc/trot_feedback.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/anymal_c/mpc/trot_feedback.py -------------------------------------------------------------------------------- /examples/icub/icub_description/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/README.md -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_chest.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_chest.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_head.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_head.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_ankle_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_ankle_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_arm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_arm.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_foot.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_foot.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_forearm.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_hand.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_hand.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_hip_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_hip_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_hip_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_hip_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_shank.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_shank.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_shoulder_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_shoulder_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_shoulder_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_shoulder_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_thigh.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_l_thigh.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_lap_belt_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_lap_belt_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_neck_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_neck_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_neck_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_neck_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_ankle_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_ankle_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_arm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_arm.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_foot.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_foot.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_forearm.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_hand.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_hand.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_hip_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_hip_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_hip_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_hip_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_shank.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_shank.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_shoulder_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_shoulder_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_shoulder_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_shoulder_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_thigh.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_r_thigh.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_root_link.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/collision/icub_simple_collision_root_link.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_chest.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_chest.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_head.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_head.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_ankle_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_ankle_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_arm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_arm.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_foot.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_foot.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_forearm.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_hand.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_hand.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_hip_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_hip_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_hip_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_hip_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_shank.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_shank.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_shoulder_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_shoulder_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_shoulder_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_shoulder_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_l_thigh.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_l_thigh.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_lap_belt_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_lap_belt_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_neck_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_neck_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_neck_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_neck_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_ankle_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_ankle_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_arm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_arm.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_foot.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_foot.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_forearm.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_hand.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_hand.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_hip_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_hip_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_hip_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_hip_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_shank.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_shank.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_shoulder_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_shoulder_1.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_shoulder_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_shoulder_2.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_r_thigh.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_r_thigh.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/meshes/upmc/visual/icub_root_link.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/meshes/upmc/visual/icub_root_link.dae -------------------------------------------------------------------------------- /examples/icub/icub_description/urdf/icub.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/urdf/icub.urdf -------------------------------------------------------------------------------- /examples/icub/icub_description/urdf/icub_lower_half.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/icub_description/urdf/icub_lower_half.urdf -------------------------------------------------------------------------------- /examples/icub/mpc/icub_simulator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/mpc/icub_simulator.py -------------------------------------------------------------------------------- /examples/icub/mpc/walk.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/mpc/walk.py -------------------------------------------------------------------------------- /examples/icub/python/jump_sto.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/icub/python/jump_sto.py -------------------------------------------------------------------------------- /examples/iiwa14/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/CMakeLists.txt -------------------------------------------------------------------------------- /examples/iiwa14/config_space_ocp.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/config_space_ocp.cpp -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/hokuyo.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/hokuyo.dae -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_0.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_0.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_1.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_2.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_3.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_4.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_5.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_5.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_6.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_6.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_7.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/collision/link_7.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_0.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_0.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_1.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_2.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_3.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_4.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_5.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_5.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_6.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_6.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_7.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/meshes/iiwa14/visual/link_7.stl -------------------------------------------------------------------------------- /examples/iiwa14/iiwa_description/urdf/iiwa14.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/iiwa_description/urdf/iiwa14.urdf -------------------------------------------------------------------------------- /examples/iiwa14/ocp_benchmark.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/ocp_benchmark.cpp -------------------------------------------------------------------------------- /examples/iiwa14/python/config_space_ocp.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/python/config_space_ocp.py -------------------------------------------------------------------------------- /examples/iiwa14/task_space_ocp.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/task_space_ocp.cpp -------------------------------------------------------------------------------- /examples/iiwa14/unconstr_ocp_benchmark.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/unconstr_ocp_benchmark.cpp -------------------------------------------------------------------------------- /examples/iiwa14/unconstr_parnmpc_benchmark.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/examples/iiwa14/unconstr_parnmpc_benchmark.cpp -------------------------------------------------------------------------------- /include/robotoc/constraints/constraint_component_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/constraint_component_base.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/constraint_component_base.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/constraint_component_base.hxx -------------------------------------------------------------------------------- /include/robotoc/constraints/constraint_component_data.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/constraint_component_data.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/constraints.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/constraints.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/constraints_data.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/constraints_data.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/constraints_data.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/constraints_data.hxx -------------------------------------------------------------------------------- /include/robotoc/constraints/constraints_impl.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/constraints_impl.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/constraints_impl.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/constraints_impl.hxx -------------------------------------------------------------------------------- /include/robotoc/constraints/contact_wrench_cone.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/contact_wrench_cone.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/friction_cone.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/friction_cone.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/impact_constraint_component_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/impact_constraint_component_base.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/impact_constraint_component_base.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/impact_constraint_component_base.hxx -------------------------------------------------------------------------------- /include/robotoc/constraints/impact_friction_cone.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/impact_friction_cone.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/impact_wrench_cone.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/impact_wrench_cone.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/joint_acceleration_lower_limit.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/joint_acceleration_lower_limit.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/joint_acceleration_upper_limit.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/joint_acceleration_upper_limit.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/joint_position_lower_limit.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/joint_position_lower_limit.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/joint_position_upper_limit.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/joint_position_upper_limit.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/joint_torques_lower_limit.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/joint_torques_lower_limit.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/joint_torques_upper_limit.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/joint_torques_upper_limit.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/joint_velocity_lower_limit.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/joint_velocity_lower_limit.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/joint_velocity_upper_limit.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/joint_velocity_upper_limit.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/pdipm.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/pdipm.hpp -------------------------------------------------------------------------------- /include/robotoc/constraints/pdipm.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/constraints/pdipm.hxx -------------------------------------------------------------------------------- /include/robotoc/core/direction.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/direction.hpp -------------------------------------------------------------------------------- /include/robotoc/core/kkt_matrix.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/kkt_matrix.hpp -------------------------------------------------------------------------------- /include/robotoc/core/kkt_residual.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/kkt_residual.hpp -------------------------------------------------------------------------------- /include/robotoc/core/performance_index.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/performance_index.hpp -------------------------------------------------------------------------------- /include/robotoc/core/solution.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/solution.hpp -------------------------------------------------------------------------------- /include/robotoc/core/split_direction.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/split_direction.hpp -------------------------------------------------------------------------------- /include/robotoc/core/split_direction.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/split_direction.hxx -------------------------------------------------------------------------------- /include/robotoc/core/split_kkt_matrix.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/split_kkt_matrix.hpp -------------------------------------------------------------------------------- /include/robotoc/core/split_kkt_matrix.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/split_kkt_matrix.hxx -------------------------------------------------------------------------------- /include/robotoc/core/split_kkt_residual.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/split_kkt_residual.hpp -------------------------------------------------------------------------------- /include/robotoc/core/split_kkt_residual.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/split_kkt_residual.hxx -------------------------------------------------------------------------------- /include/robotoc/core/split_solution.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/split_solution.hpp -------------------------------------------------------------------------------- /include/robotoc/core/split_solution.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/core/split_solution.hxx -------------------------------------------------------------------------------- /include/robotoc/cost/com_cost.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/com_cost.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/com_ref_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/com_ref_base.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/configuration_space_cost.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/configuration_space_cost.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/configuration_space_ref_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/configuration_space_ref_base.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/cost_function.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/cost_function.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/cost_function_component_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/cost_function_component_base.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/cost_function_data.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/cost_function_data.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/discrete_time_com_ref.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/discrete_time_com_ref.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/discrete_time_swing_foot_ref.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/discrete_time_swing_foot_ref.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/foot_trajectory_type.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/foot_trajectory_type.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/local_contact_force_cost.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/local_contact_force_cost.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/periodic_com_ref.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/periodic_com_ref.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/periodic_swing_foot_ref.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/periodic_swing_foot_ref.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/task_space_3d_cost.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/task_space_3d_cost.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/task_space_3d_ref_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/task_space_3d_ref_base.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/task_space_6d_cost.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/task_space_6d_cost.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/task_space_6d_ref_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/task_space_6d_ref_base.hpp -------------------------------------------------------------------------------- /include/robotoc/cost/trot_swing_foot_ref.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/cost/trot_swing_foot_ref.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/contact_dynamics.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/contact_dynamics.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/contact_dynamics_data.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/contact_dynamics_data.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/contact_dynamics_data.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/contact_dynamics_data.hxx -------------------------------------------------------------------------------- /include/robotoc/dynamics/impact_dynamics.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/impact_dynamics.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/impact_state_equation.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/impact_state_equation.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/state_equation.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/state_equation.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/state_equation_data.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/state_equation_data.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/switching_constraint.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/switching_constraint.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/switching_constraint_data.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/switching_constraint_data.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/terminal_state_equation.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/terminal_state_equation.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/unconstr_dynamics.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/unconstr_dynamics.hpp -------------------------------------------------------------------------------- /include/robotoc/dynamics/unconstr_state_equation.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/dynamics/unconstr_state_equation.hpp -------------------------------------------------------------------------------- /include/robotoc/line_search/line_search.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/line_search/line_search.hpp -------------------------------------------------------------------------------- /include/robotoc/line_search/line_search_filter.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/line_search/line_search_filter.hpp -------------------------------------------------------------------------------- /include/robotoc/line_search/line_search_settings.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/line_search/line_search_settings.hpp -------------------------------------------------------------------------------- /include/robotoc/line_search/unconstr_line_search.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/line_search/unconstr_line_search.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/biped_walk_foot_step_planner.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/biped_walk_foot_step_planner.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/contact_planner_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/contact_planner_base.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/control_policy.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/control_policy.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/crawl_foot_step_planner.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/crawl_foot_step_planner.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/flying_trot_foot_step_planner.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/flying_trot_foot_step_planner.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/jump_foot_step_planner.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/jump_foot_step_planner.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/moving_window_filter.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/moving_window_filter.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/mpc_biped_walk.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/mpc_biped_walk.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/mpc_crawl.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/mpc_crawl.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/mpc_flying_trot.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/mpc_flying_trot.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/mpc_jump.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/mpc_jump.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/mpc_pace.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/mpc_pace.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/mpc_periodic_com_ref.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/mpc_periodic_com_ref.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/mpc_periodic_configuration_ref.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/mpc_periodic_configuration_ref.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/mpc_periodic_swing_foot_ref.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/mpc_periodic_swing_foot_ref.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/mpc_trot.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/mpc_trot.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/pace_foot_step_planner.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/pace_foot_step_planner.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/raibert_heuristic.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/raibert_heuristic.hpp -------------------------------------------------------------------------------- /include/robotoc/mpc/trot_foot_step_planner.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/mpc/trot_foot_step_planner.hpp -------------------------------------------------------------------------------- /include/robotoc/ocp/direct_multiple_shooting.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/ocp/direct_multiple_shooting.hpp -------------------------------------------------------------------------------- /include/robotoc/ocp/discretization_method.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/ocp/discretization_method.hpp -------------------------------------------------------------------------------- /include/robotoc/ocp/grid_info.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/ocp/grid_info.hpp -------------------------------------------------------------------------------- /include/robotoc/ocp/impact_stage.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/ocp/impact_stage.hpp -------------------------------------------------------------------------------- /include/robotoc/ocp/intermediate_stage.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/ocp/intermediate_stage.hpp -------------------------------------------------------------------------------- /include/robotoc/ocp/ocp.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/ocp/ocp.hpp -------------------------------------------------------------------------------- /include/robotoc/ocp/ocp_data.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/ocp/ocp_data.hpp -------------------------------------------------------------------------------- /include/robotoc/ocp/terminal_stage.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/ocp/terminal_stage.hpp -------------------------------------------------------------------------------- /include/robotoc/ocp/time_discretization.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/ocp/time_discretization.hpp -------------------------------------------------------------------------------- /include/robotoc/parnmpc/unconstr_backward_correction.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/parnmpc/unconstr_backward_correction.hpp -------------------------------------------------------------------------------- /include/robotoc/parnmpc/unconstr_kkt_matrix_inverter.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/parnmpc/unconstr_kkt_matrix_inverter.hpp -------------------------------------------------------------------------------- /include/robotoc/parnmpc/unconstr_kkt_matrix_inverter.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/parnmpc/unconstr_kkt_matrix_inverter.hxx -------------------------------------------------------------------------------- /include/robotoc/parnmpc/unconstr_split_backward_correction.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/parnmpc/unconstr_split_backward_correction.hpp -------------------------------------------------------------------------------- /include/robotoc/planner/contact_sequence.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/planner/contact_sequence.hpp -------------------------------------------------------------------------------- /include/robotoc/planner/discrete_event.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/planner/discrete_event.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/backward_riccati_recursion_factorizer.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/backward_riccati_recursion_factorizer.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/lqr_policy.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/lqr_policy.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/riccati_factorization.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/riccati_factorization.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/riccati_factorizer.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/riccati_factorizer.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/riccati_recursion.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/riccati_recursion.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/split_constrained_riccati_factorization.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/split_constrained_riccati_factorization.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/split_constrained_riccati_factorization.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/split_constrained_riccati_factorization.hxx -------------------------------------------------------------------------------- /include/robotoc/riccati/split_riccati_factorization.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/split_riccati_factorization.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/split_riccati_factorization.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/split_riccati_factorization.hxx -------------------------------------------------------------------------------- /include/robotoc/riccati/sto_policy.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/sto_policy.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/unconstr_backward_riccati_recursion_factorizer.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/unconstr_backward_riccati_recursion_factorizer.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/unconstr_riccati_factorizer.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/unconstr_riccati_factorizer.hpp -------------------------------------------------------------------------------- /include/robotoc/riccati/unconstr_riccati_recursion.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/riccati/unconstr_riccati_recursion.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/contact_model_info.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/contact_model_info.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/contact_status.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/contact_status.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/contact_status.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/contact_status.hxx -------------------------------------------------------------------------------- /include/robotoc/robot/impact_status.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/impact_status.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/impact_status.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/impact_status.hxx -------------------------------------------------------------------------------- /include/robotoc/robot/point_contact.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/point_contact.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/point_contact.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/point_contact.hxx -------------------------------------------------------------------------------- /include/robotoc/robot/robot.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/robot.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/robot.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/robot.hxx -------------------------------------------------------------------------------- /include/robotoc/robot/robot_model_info.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/robot_model_info.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/robot_properties.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/robot_properties.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/se3.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/se3.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/se3_jacobian_inverse.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/se3_jacobian_inverse.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/se3_jacobian_inverse.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/se3_jacobian_inverse.hxx -------------------------------------------------------------------------------- /include/robotoc/robot/surface_contact.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/surface_contact.hpp -------------------------------------------------------------------------------- /include/robotoc/robot/surface_contact.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/robot/surface_contact.hxx -------------------------------------------------------------------------------- /include/robotoc/solver/interpolation_order.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/solver/interpolation_order.hpp -------------------------------------------------------------------------------- /include/robotoc/solver/ocp_solver.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/solver/ocp_solver.hpp -------------------------------------------------------------------------------- /include/robotoc/solver/solution_interpolator.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/solver/solution_interpolator.hpp -------------------------------------------------------------------------------- /include/robotoc/solver/solver_options.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/solver/solver_options.hpp -------------------------------------------------------------------------------- /include/robotoc/solver/solver_statistics.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/solver/solver_statistics.hpp -------------------------------------------------------------------------------- /include/robotoc/solver/unconstr_ocp_solver.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/solver/unconstr_ocp_solver.hpp -------------------------------------------------------------------------------- /include/robotoc/solver/unconstr_parnmpc_solver.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/solver/unconstr_parnmpc_solver.hpp -------------------------------------------------------------------------------- /include/robotoc/sto/sto_constraints.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/sto/sto_constraints.hpp -------------------------------------------------------------------------------- /include/robotoc/sto/sto_cost_function.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/sto/sto_cost_function.hpp -------------------------------------------------------------------------------- /include/robotoc/sto/sto_cost_function_component_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/sto/sto_cost_function_component_base.hpp -------------------------------------------------------------------------------- /include/robotoc/sto/switching_time_optimization.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/sto/switching_time_optimization.hpp -------------------------------------------------------------------------------- /include/robotoc/unconstr/parnmpc_intermediate_stage.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/unconstr/parnmpc_intermediate_stage.hpp -------------------------------------------------------------------------------- /include/robotoc/unconstr/parnmpc_terminal_stage.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/unconstr/parnmpc_terminal_stage.hpp -------------------------------------------------------------------------------- /include/robotoc/unconstr/unconstr_direct_multiple_shooting.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/unconstr/unconstr_direct_multiple_shooting.hpp -------------------------------------------------------------------------------- /include/robotoc/unconstr/unconstr_intermediate_stage.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/unconstr/unconstr_intermediate_stage.hpp -------------------------------------------------------------------------------- /include/robotoc/unconstr/unconstr_ocp_data.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/unconstr/unconstr_ocp_data.hpp -------------------------------------------------------------------------------- /include/robotoc/unconstr/unconstr_terminal_stage.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/unconstr/unconstr_terminal_stage.hpp -------------------------------------------------------------------------------- /include/robotoc/utils/aligned_deque.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/aligned_deque.hpp -------------------------------------------------------------------------------- /include/robotoc/utils/aligned_unordered_map.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/aligned_unordered_map.hpp -------------------------------------------------------------------------------- /include/robotoc/utils/aligned_vector.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/aligned_vector.hpp -------------------------------------------------------------------------------- /include/robotoc/utils/derivative_checker.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/derivative_checker.hpp -------------------------------------------------------------------------------- /include/robotoc/utils/numerics.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/numerics.hpp -------------------------------------------------------------------------------- /include/robotoc/utils/ocp_benchmarker.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/ocp_benchmarker.hpp -------------------------------------------------------------------------------- /include/robotoc/utils/ocp_benchmarker.hxx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/ocp_benchmarker.hxx -------------------------------------------------------------------------------- /include/robotoc/utils/pybind11_macros.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/pybind11_macros.hpp -------------------------------------------------------------------------------- /include/robotoc/utils/rotation.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/rotation.hpp -------------------------------------------------------------------------------- /include/robotoc/utils/timer.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/include/robotoc/utils/timer.hpp -------------------------------------------------------------------------------- /requirements.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/requirements.txt -------------------------------------------------------------------------------- /src/constraints/constraint_component_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/constraint_component_base.cpp -------------------------------------------------------------------------------- /src/constraints/constraint_component_data.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/constraint_component_data.cpp -------------------------------------------------------------------------------- /src/constraints/constraints.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/constraints.cpp -------------------------------------------------------------------------------- /src/constraints/constraints_data.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/constraints_data.cpp -------------------------------------------------------------------------------- /src/constraints/contact_wrench_cone.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/contact_wrench_cone.cpp -------------------------------------------------------------------------------- /src/constraints/friction_cone.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/friction_cone.cpp -------------------------------------------------------------------------------- /src/constraints/impact_constraint_component_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/impact_constraint_component_base.cpp -------------------------------------------------------------------------------- /src/constraints/impact_friction_cone.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/impact_friction_cone.cpp -------------------------------------------------------------------------------- /src/constraints/impact_wrench_cone.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/impact_wrench_cone.cpp -------------------------------------------------------------------------------- /src/constraints/joint_acceleration_lower_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/joint_acceleration_lower_limit.cpp -------------------------------------------------------------------------------- /src/constraints/joint_acceleration_upper_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/joint_acceleration_upper_limit.cpp -------------------------------------------------------------------------------- /src/constraints/joint_position_lower_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/joint_position_lower_limit.cpp -------------------------------------------------------------------------------- /src/constraints/joint_position_upper_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/joint_position_upper_limit.cpp -------------------------------------------------------------------------------- /src/constraints/joint_torques_lower_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/joint_torques_lower_limit.cpp -------------------------------------------------------------------------------- /src/constraints/joint_torques_upper_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/joint_torques_upper_limit.cpp -------------------------------------------------------------------------------- /src/constraints/joint_velocity_lower_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/joint_velocity_lower_limit.cpp -------------------------------------------------------------------------------- /src/constraints/joint_velocity_upper_limit.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/constraints/joint_velocity_upper_limit.cpp -------------------------------------------------------------------------------- /src/core/direction.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/core/direction.cpp -------------------------------------------------------------------------------- /src/core/kkt_matrix.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/core/kkt_matrix.cpp -------------------------------------------------------------------------------- /src/core/kkt_residual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/core/kkt_residual.cpp -------------------------------------------------------------------------------- /src/core/performance_index.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/core/performance_index.cpp -------------------------------------------------------------------------------- /src/core/solution.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/core/solution.cpp -------------------------------------------------------------------------------- /src/core/split_direction.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/core/split_direction.cpp -------------------------------------------------------------------------------- /src/core/split_kkt_matrix.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/core/split_kkt_matrix.cpp -------------------------------------------------------------------------------- /src/core/split_kkt_residual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/core/split_kkt_residual.cpp -------------------------------------------------------------------------------- /src/core/split_solution.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/core/split_solution.cpp -------------------------------------------------------------------------------- /src/cost/com_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/com_cost.cpp -------------------------------------------------------------------------------- /src/cost/configuration_space_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/configuration_space_cost.cpp -------------------------------------------------------------------------------- /src/cost/cost_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/cost_function.cpp -------------------------------------------------------------------------------- /src/cost/cost_function_data.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/cost_function_data.cpp -------------------------------------------------------------------------------- /src/cost/discrete_time_com_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/discrete_time_com_ref.cpp -------------------------------------------------------------------------------- /src/cost/discrete_time_swing_foot_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/discrete_time_swing_foot_ref.cpp -------------------------------------------------------------------------------- /src/cost/local_contact_force_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/local_contact_force_cost.cpp -------------------------------------------------------------------------------- /src/cost/periodic_com_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/periodic_com_ref.cpp -------------------------------------------------------------------------------- /src/cost/periodic_swing_foot_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/periodic_swing_foot_ref.cpp -------------------------------------------------------------------------------- /src/cost/task_space_3d_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/task_space_3d_cost.cpp -------------------------------------------------------------------------------- /src/cost/task_space_6d_cost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/cost/task_space_6d_cost.cpp -------------------------------------------------------------------------------- /src/dynamics/contact_dynamics.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/contact_dynamics.cpp -------------------------------------------------------------------------------- /src/dynamics/contact_dynamics_data.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/contact_dynamics_data.cpp -------------------------------------------------------------------------------- /src/dynamics/impact_dynamics.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/impact_dynamics.cpp -------------------------------------------------------------------------------- /src/dynamics/impact_state_equation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/impact_state_equation.cpp -------------------------------------------------------------------------------- /src/dynamics/state_equation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/state_equation.cpp -------------------------------------------------------------------------------- /src/dynamics/state_equation_data.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/state_equation_data.cpp -------------------------------------------------------------------------------- /src/dynamics/switching_constraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/switching_constraint.cpp -------------------------------------------------------------------------------- /src/dynamics/switching_constraint_data.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/switching_constraint_data.cpp -------------------------------------------------------------------------------- /src/dynamics/terminal_state_equation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/terminal_state_equation.cpp -------------------------------------------------------------------------------- /src/dynamics/unconstr_dynamics.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/unconstr_dynamics.cpp -------------------------------------------------------------------------------- /src/dynamics/unconstr_state_equation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/dynamics/unconstr_state_equation.cpp -------------------------------------------------------------------------------- /src/line_search/line_search.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/line_search/line_search.cpp -------------------------------------------------------------------------------- /src/line_search/line_search_filter.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/line_search/line_search_filter.cpp -------------------------------------------------------------------------------- /src/line_search/line_search_settings.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/line_search/line_search_settings.cpp -------------------------------------------------------------------------------- /src/line_search/unconstr_line_search.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/line_search/unconstr_line_search.cpp -------------------------------------------------------------------------------- /src/mpc/biped_walk_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/biped_walk_foot_step_planner.cpp -------------------------------------------------------------------------------- /src/mpc/contact_planner_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/contact_planner_base.cpp -------------------------------------------------------------------------------- /src/mpc/control_policy.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/control_policy.cpp -------------------------------------------------------------------------------- /src/mpc/crawl_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/crawl_foot_step_planner.cpp -------------------------------------------------------------------------------- /src/mpc/flying_trot_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/flying_trot_foot_step_planner.cpp -------------------------------------------------------------------------------- /src/mpc/jump_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/jump_foot_step_planner.cpp -------------------------------------------------------------------------------- /src/mpc/mpc_biped_walk.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/mpc_biped_walk.cpp -------------------------------------------------------------------------------- /src/mpc/mpc_crawl.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/mpc_crawl.cpp -------------------------------------------------------------------------------- /src/mpc/mpc_flying_trot.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/mpc_flying_trot.cpp -------------------------------------------------------------------------------- /src/mpc/mpc_jump.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/mpc_jump.cpp -------------------------------------------------------------------------------- /src/mpc/mpc_pace.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/mpc_pace.cpp -------------------------------------------------------------------------------- /src/mpc/mpc_periodic_com_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/mpc_periodic_com_ref.cpp -------------------------------------------------------------------------------- /src/mpc/mpc_periodic_configuration_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/mpc_periodic_configuration_ref.cpp -------------------------------------------------------------------------------- /src/mpc/mpc_periodic_swing_foot_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/mpc_periodic_swing_foot_ref.cpp -------------------------------------------------------------------------------- /src/mpc/mpc_trot.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/mpc_trot.cpp -------------------------------------------------------------------------------- /src/mpc/pace_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/pace_foot_step_planner.cpp -------------------------------------------------------------------------------- /src/mpc/raibert_heuristic.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/raibert_heuristic.cpp -------------------------------------------------------------------------------- /src/mpc/trot_foot_step_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/mpc/trot_foot_step_planner.cpp -------------------------------------------------------------------------------- /src/ocp/direct_multiple_shooting.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/ocp/direct_multiple_shooting.cpp -------------------------------------------------------------------------------- /src/ocp/grid_info.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/ocp/grid_info.cpp -------------------------------------------------------------------------------- /src/ocp/impact_stage.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/ocp/impact_stage.cpp -------------------------------------------------------------------------------- /src/ocp/intermediate_stage.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/ocp/intermediate_stage.cpp -------------------------------------------------------------------------------- /src/ocp/ocp.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/ocp/ocp.cpp -------------------------------------------------------------------------------- /src/ocp/terminal_stage.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/ocp/terminal_stage.cpp -------------------------------------------------------------------------------- /src/ocp/time_discretization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/ocp/time_discretization.cpp -------------------------------------------------------------------------------- /src/parnmpc/unconstr_backward_correction.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/parnmpc/unconstr_backward_correction.cpp -------------------------------------------------------------------------------- /src/parnmpc/unconstr_split_backward_correction.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/parnmpc/unconstr_split_backward_correction.cpp -------------------------------------------------------------------------------- /src/planner/contact_sequence.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/planner/contact_sequence.cpp -------------------------------------------------------------------------------- /src/planner/discrete_event.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/planner/discrete_event.cpp -------------------------------------------------------------------------------- /src/riccati/backward_riccati_recursion_factorizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/riccati/backward_riccati_recursion_factorizer.cpp -------------------------------------------------------------------------------- /src/riccati/riccati_factorization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/riccati/riccati_factorization.cpp -------------------------------------------------------------------------------- /src/riccati/riccati_factorizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/riccati/riccati_factorizer.cpp -------------------------------------------------------------------------------- /src/riccati/riccati_recursion.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/riccati/riccati_recursion.cpp -------------------------------------------------------------------------------- /src/riccati/split_constrained_riccati_factorization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/riccati/split_constrained_riccati_factorization.cpp -------------------------------------------------------------------------------- /src/riccati/split_riccati_factorization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/riccati/split_riccati_factorization.cpp -------------------------------------------------------------------------------- /src/riccati/unconstr_backward_riccati_recursion_factorizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/riccati/unconstr_backward_riccati_recursion_factorizer.cpp -------------------------------------------------------------------------------- /src/riccati/unconstr_riccati_factorizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/riccati/unconstr_riccati_factorizer.cpp -------------------------------------------------------------------------------- /src/riccati/unconstr_riccati_recursion.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/riccati/unconstr_riccati_recursion.cpp -------------------------------------------------------------------------------- /src/robot/contact_model_info.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/robot/contact_model_info.cpp -------------------------------------------------------------------------------- /src/robot/contact_status.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/robot/contact_status.cpp -------------------------------------------------------------------------------- /src/robot/impact_status.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/robot/impact_status.cpp -------------------------------------------------------------------------------- /src/robot/point_contact.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/robot/point_contact.cpp -------------------------------------------------------------------------------- /src/robot/robot.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/robot/robot.cpp -------------------------------------------------------------------------------- /src/robot/robot_model_info.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/robot/robot_model_info.cpp -------------------------------------------------------------------------------- /src/robot/surface_contact.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/robot/surface_contact.cpp -------------------------------------------------------------------------------- /src/solver/ocp_solver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/solver/ocp_solver.cpp -------------------------------------------------------------------------------- /src/solver/solution_interpolator.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/solver/solution_interpolator.cpp -------------------------------------------------------------------------------- /src/solver/solver_options.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/solver/solver_options.cpp -------------------------------------------------------------------------------- /src/solver/solver_statistics.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/solver/solver_statistics.cpp -------------------------------------------------------------------------------- /src/solver/unconstr_ocp_solver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/solver/unconstr_ocp_solver.cpp -------------------------------------------------------------------------------- /src/solver/unconstr_parnmpc_solver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/solver/unconstr_parnmpc_solver.cpp -------------------------------------------------------------------------------- /src/sto/sto_constraints.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/sto/sto_constraints.cpp -------------------------------------------------------------------------------- /src/sto/sto_cost_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/sto/sto_cost_function.cpp -------------------------------------------------------------------------------- /src/sto/switching_time_optimization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/sto/switching_time_optimization.cpp -------------------------------------------------------------------------------- /src/unconstr/parnmpc_intermediate_stage.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/unconstr/parnmpc_intermediate_stage.cpp -------------------------------------------------------------------------------- /src/unconstr/parnmpc_terminal_stage.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/unconstr/parnmpc_terminal_stage.cpp -------------------------------------------------------------------------------- /src/unconstr/unconstr_direct_multiple_shooting.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/unconstr/unconstr_direct_multiple_shooting.cpp -------------------------------------------------------------------------------- /src/unconstr/unconstr_intermediate_stage.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/unconstr/unconstr_intermediate_stage.cpp -------------------------------------------------------------------------------- /src/unconstr/unconstr_terminal_stage.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/unconstr/unconstr_terminal_stage.cpp -------------------------------------------------------------------------------- /src/utils/derivative_checker.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/src/utils/derivative_checker.cpp -------------------------------------------------------------------------------- /test/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/CMakeLists.txt -------------------------------------------------------------------------------- /test/cmake/gtest.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cmake/gtest.cmake -------------------------------------------------------------------------------- /test/constraints/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/CMakeLists.txt -------------------------------------------------------------------------------- /test/constraints/constraint_component_data_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/constraint_component_data_test.cpp -------------------------------------------------------------------------------- /test/constraints/constraints_data_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/constraints_data_test.cpp -------------------------------------------------------------------------------- /test/constraints/constraints_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/constraints_test.cpp -------------------------------------------------------------------------------- /test/constraints/contact_wrench_cone_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/contact_wrench_cone_test.cpp -------------------------------------------------------------------------------- /test/constraints/friction_cone_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/friction_cone_test.cpp -------------------------------------------------------------------------------- /test/constraints/impact_friction_cone_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/impact_friction_cone_test.cpp -------------------------------------------------------------------------------- /test/constraints/impact_wrench_cone_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/impact_wrench_cone_test.cpp -------------------------------------------------------------------------------- /test/constraints/joint_acceleration_lower_limit_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/joint_acceleration_lower_limit_test.cpp -------------------------------------------------------------------------------- /test/constraints/joint_acceleration_upper_limit_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/joint_acceleration_upper_limit_test.cpp -------------------------------------------------------------------------------- /test/constraints/joint_position_lower_limit_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/joint_position_lower_limit_test.cpp -------------------------------------------------------------------------------- /test/constraints/joint_position_upper_limit_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/joint_position_upper_limit_test.cpp -------------------------------------------------------------------------------- /test/constraints/joint_torques_lower_limit_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/joint_torques_lower_limit_test.cpp -------------------------------------------------------------------------------- /test/constraints/joint_torques_upper_limit_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/joint_torques_upper_limit_test.cpp -------------------------------------------------------------------------------- /test/constraints/joint_velocity_lower_limit_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/joint_velocity_lower_limit_test.cpp -------------------------------------------------------------------------------- /test/constraints/joint_velocity_upper_limit_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/joint_velocity_upper_limit_test.cpp -------------------------------------------------------------------------------- /test/constraints/pdipm_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/constraints/pdipm_test.cpp -------------------------------------------------------------------------------- /test/core/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/core/CMakeLists.txt -------------------------------------------------------------------------------- /test/core/split_direction_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/core/split_direction_test.cpp -------------------------------------------------------------------------------- /test/core/split_kkt_matrix_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/core/split_kkt_matrix_test.cpp -------------------------------------------------------------------------------- /test/core/split_kkt_residual_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/core/split_kkt_residual_test.cpp -------------------------------------------------------------------------------- /test/core/split_solution_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/core/split_solution_test.cpp -------------------------------------------------------------------------------- /test/cost/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cost/CMakeLists.txt -------------------------------------------------------------------------------- /test/cost/com_cost_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cost/com_cost_test.cpp -------------------------------------------------------------------------------- /test/cost/configuration_space_cost_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cost/configuration_space_cost_test.cpp -------------------------------------------------------------------------------- /test/cost/cost_function_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cost/cost_function_test.cpp -------------------------------------------------------------------------------- /test/cost/discrete_time_com_ref.cpp: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /test/cost/discrete_time_swing_foot_ref_test.cpp: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /test/cost/local_contact_force_cost_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cost/local_contact_force_cost_test.cpp -------------------------------------------------------------------------------- /test/cost/periodic_com_ref_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cost/periodic_com_ref_test.cpp -------------------------------------------------------------------------------- /test/cost/periodic_swing_foot_ref_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cost/periodic_swing_foot_ref_test.cpp -------------------------------------------------------------------------------- /test/cost/task_space_3d_cost_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cost/task_space_3d_cost_test.cpp -------------------------------------------------------------------------------- /test/cost/task_space_6d_cost_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/cost/task_space_6d_cost_test.cpp -------------------------------------------------------------------------------- /test/dynamics/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/dynamics/CMakeLists.txt -------------------------------------------------------------------------------- /test/dynamics/contact_dynamics_data_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/dynamics/contact_dynamics_data_test.cpp -------------------------------------------------------------------------------- /test/dynamics/contact_dynamics_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/dynamics/contact_dynamics_test.cpp -------------------------------------------------------------------------------- /test/dynamics/impact_dynamics_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/dynamics/impact_dynamics_test.cpp -------------------------------------------------------------------------------- /test/dynamics/impact_state_equation_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/dynamics/impact_state_equation_test.cpp -------------------------------------------------------------------------------- /test/dynamics/state_equation_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/dynamics/state_equation_test.cpp -------------------------------------------------------------------------------- /test/dynamics/switching_constraint_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/dynamics/switching_constraint_test.cpp -------------------------------------------------------------------------------- /test/dynamics/terminal_state_equation_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/dynamics/terminal_state_equation_test.cpp -------------------------------------------------------------------------------- /test/dynamics/unconstr_dynamics_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/dynamics/unconstr_dynamics_test.cpp -------------------------------------------------------------------------------- /test/line_search/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/line_search/CMakeLists.txt -------------------------------------------------------------------------------- /test/line_search/line_search_filter_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/line_search/line_search_filter_test.cpp -------------------------------------------------------------------------------- /test/line_search/line_search_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/line_search/line_search_test.cpp -------------------------------------------------------------------------------- /test/line_search/unconstr_line_search_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/line_search/unconstr_line_search_test.cpp -------------------------------------------------------------------------------- /test/mpc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/mpc/CMakeLists.txt -------------------------------------------------------------------------------- /test/mpc/biped_walk_foot_step_planner_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/mpc/biped_walk_foot_step_planner_test.cpp -------------------------------------------------------------------------------- /test/mpc/crawl_foot_step_planner_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/mpc/crawl_foot_step_planner_test.cpp -------------------------------------------------------------------------------- /test/mpc/flying_trot_foot_step_planner_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/mpc/flying_trot_foot_step_planner_test.cpp -------------------------------------------------------------------------------- /test/mpc/jump_foot_step_planner_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/mpc/jump_foot_step_planner_test.cpp -------------------------------------------------------------------------------- /test/mpc/moving_window_filter_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/mpc/moving_window_filter_test.cpp -------------------------------------------------------------------------------- /test/mpc/pace_foot_step_planner_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/mpc/pace_foot_step_planner_test.cpp -------------------------------------------------------------------------------- /test/mpc/raibert_heuristic_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/mpc/raibert_heuristic_test.cpp -------------------------------------------------------------------------------- /test/mpc/trot_foot_step_planner_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/mpc/trot_foot_step_planner_test.cpp -------------------------------------------------------------------------------- /test/ocp/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/ocp/CMakeLists.txt -------------------------------------------------------------------------------- /test/ocp/direct_multiple_shooting_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/ocp/direct_multiple_shooting_test.cpp -------------------------------------------------------------------------------- /test/ocp/impact_stage_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/ocp/impact_stage_test.cpp -------------------------------------------------------------------------------- /test/ocp/intermediate_stage_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/ocp/intermediate_stage_test.cpp -------------------------------------------------------------------------------- /test/ocp/terminal_stage_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/ocp/terminal_stage_test.cpp -------------------------------------------------------------------------------- /test/ocp/time_discretization_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/ocp/time_discretization_test.cpp -------------------------------------------------------------------------------- /test/parnmpc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/parnmpc/CMakeLists.txt -------------------------------------------------------------------------------- /test/parnmpc/unconstr_kkt_matrix_inverter_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/parnmpc/unconstr_kkt_matrix_inverter_test.cpp -------------------------------------------------------------------------------- /test/parnmpc/unconstr_split_backward_correction_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/parnmpc/unconstr_split_backward_correction_test.cpp -------------------------------------------------------------------------------- /test/planner/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/planner/CMakeLists.txt -------------------------------------------------------------------------------- /test/planner/contact_sequence_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/planner/contact_sequence_test.cpp -------------------------------------------------------------------------------- /test/planner/discrete_event_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/planner/discrete_event_test.cpp -------------------------------------------------------------------------------- /test/riccati/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/riccati/CMakeLists.txt -------------------------------------------------------------------------------- /test/riccati/backward_riccati_recursion_factorizer_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/riccati/backward_riccati_recursion_factorizer_test.cpp -------------------------------------------------------------------------------- /test/riccati/riccati_factorizer_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/riccati/riccati_factorizer_test.cpp -------------------------------------------------------------------------------- /test/riccati/riccati_recursion_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/riccati/riccati_recursion_test.cpp -------------------------------------------------------------------------------- /test/riccati/split_riccati_factorization_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/riccati/split_riccati_factorization_test.cpp -------------------------------------------------------------------------------- /test/riccati/unconstr_backward_riccati_recursion_factorizer_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/riccati/unconstr_backward_riccati_recursion_factorizer_test.cpp -------------------------------------------------------------------------------- /test/riccati/unconstr_riccati_factorizer_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/riccati/unconstr_riccati_factorizer_test.cpp -------------------------------------------------------------------------------- /test/riccati/unconstr_riccati_recursion_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/riccati/unconstr_riccati_recursion_test.cpp -------------------------------------------------------------------------------- /test/robot/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/robot/CMakeLists.txt -------------------------------------------------------------------------------- /test/robot/contact_status_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/robot/contact_status_test.cpp -------------------------------------------------------------------------------- /test/robot/impact_status_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/robot/impact_status_test.cpp -------------------------------------------------------------------------------- /test/robot/point_contact_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/robot/point_contact_test.cpp -------------------------------------------------------------------------------- /test/robot/robot_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/robot/robot_test.cpp -------------------------------------------------------------------------------- /test/robot/se3_jacobian_inverse_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/robot/se3_jacobian_inverse_test.cpp -------------------------------------------------------------------------------- /test/robot/surface_contact_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/robot/surface_contact_test.cpp -------------------------------------------------------------------------------- /test/solver/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/solver/CMakeLists.txt -------------------------------------------------------------------------------- /test/solver/ocp_solver_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/solver/ocp_solver_test.cpp -------------------------------------------------------------------------------- /test/solver/solver_options_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/solver/solver_options_test.cpp -------------------------------------------------------------------------------- /test/solver/solver_statistics_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/solver/solver_statistics_test.cpp -------------------------------------------------------------------------------- /test/solver/unconstr_ocp_solver_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/solver/unconstr_ocp_solver_test.cpp -------------------------------------------------------------------------------- /test/solver/unconstr_parnmpc_solver_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/solver/unconstr_parnmpc_solver_test.cpp -------------------------------------------------------------------------------- /test/sto/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/sto/CMakeLists.txt -------------------------------------------------------------------------------- /test/sto/sto_constraints_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/sto/sto_constraints_test.cpp -------------------------------------------------------------------------------- /test/sto/sto_cost_function_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/sto/sto_cost_function_test.cpp -------------------------------------------------------------------------------- /test/test_helper/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/CMakeLists.txt -------------------------------------------------------------------------------- /test/test_helper/constraints_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/constraints_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/constraints_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/constraints_factory.hpp -------------------------------------------------------------------------------- /test/test_helper/contact_sequence_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/contact_sequence_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/contact_sequence_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/contact_sequence_factory.hpp -------------------------------------------------------------------------------- /test/test_helper/contact_status_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/contact_status_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/contact_status_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/contact_status_factory.hpp -------------------------------------------------------------------------------- /test/test_helper/cost_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/cost_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/cost_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/cost_factory.hpp -------------------------------------------------------------------------------- /test/test_helper/direction_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/direction_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/direction_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/direction_factory.hpp -------------------------------------------------------------------------------- /test/test_helper/kkt_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/kkt_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/kkt_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/kkt_factory.hpp -------------------------------------------------------------------------------- /test/test_helper/riccati_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/riccati_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/riccati_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/riccati_factory.hpp -------------------------------------------------------------------------------- /test/test_helper/robot_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/robot_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/robot_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/robot_factory.hpp -------------------------------------------------------------------------------- /test/test_helper/solution_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/solution_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/solution_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/solution_factory.hpp -------------------------------------------------------------------------------- /test/test_helper/test_helper.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/test_helper.hpp -------------------------------------------------------------------------------- /test/test_helper/urdf_factory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/urdf_factory.cpp -------------------------------------------------------------------------------- /test/test_helper/urdf_factory.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/test_helper/urdf_factory.hpp -------------------------------------------------------------------------------- /test/unconstr/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/unconstr/CMakeLists.txt -------------------------------------------------------------------------------- /test/unconstr/parnmpc_intermediate_stage_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/unconstr/parnmpc_intermediate_stage_test.cpp -------------------------------------------------------------------------------- /test/unconstr/parnmpc_terminal_stage_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/unconstr/parnmpc_terminal_stage_test.cpp -------------------------------------------------------------------------------- /test/unconstr/unconstr_intermediate_stage_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/unconstr/unconstr_intermediate_stage_test.cpp -------------------------------------------------------------------------------- /test/unconstr/unconstr_terminal_stage_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/unconstr/unconstr_terminal_stage_test.cpp -------------------------------------------------------------------------------- /test/urdf/anymal/anymal.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/urdf/anymal/anymal.urdf -------------------------------------------------------------------------------- /test/urdf/icub/icub.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/urdf/icub/icub.urdf -------------------------------------------------------------------------------- /test/urdf/iiwa14/iiwa14.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mayataka/robotoc/HEAD/test/urdf/iiwa14/iiwa14.urdf --------------------------------------------------------------------------------