├── .clang-format ├── .devcontainer └── devcontainer.json ├── .github ├── ISSUE_TEMPLATE │ ├── bug_report.md │ └── feature_request.md └── workflows │ ├── build_test.yml │ └── format_test.yml ├── .gitignore ├── .gitmodules ├── CODE_OF_CONDUCT.md ├── LICENCE.txt ├── Makefile ├── README.md ├── dependencies.txt ├── docker ├── Dockerfile ├── image_build.bash └── launch_wb_mpc.bash ├── humanoid_nmpc ├── humanoid_centroidal_mpc │ ├── CMakeLists.txt │ ├── include │ │ └── humanoid_centroidal_mpc │ │ │ ├── CentroidalMpcInterface.h │ │ │ ├── command │ │ │ └── CentroidalMpcTargetTrajectoriesCalculator.h │ │ │ ├── common │ │ │ └── CentroidalMpcRobotModel.h │ │ │ ├── constraint │ │ │ ├── JointMimicKinematicConstraint.h │ │ │ ├── NormalVelocityConstraintCppAd.h │ │ │ └── ZeroVelocityConstraintCppAd.h │ │ │ ├── cost │ │ │ ├── CentroidalMpcEndEffectorFootCost.h │ │ │ └── ICPCost.h │ │ │ ├── dynamics │ │ │ ├── CentroidalDynamicsAD.h │ │ │ └── DynamicsHelperFunctions.h │ │ │ ├── initialization │ │ │ └── CentroidalWeightCompInitializer.h │ │ │ ├── mrt │ │ │ └── CentroidalMpcMrtJointController.h │ │ │ └── test │ │ │ └── CentroidalTestingModelInterface.h │ ├── package.xml │ ├── src │ │ ├── CentroidalMpcInterface.cpp │ │ ├── command │ │ │ └── CentroidalMpcTargetTrajectoriesCalculator.cpp │ │ ├── constraint │ │ │ ├── JointMimicKinematicConstraint.cpp │ │ │ ├── NormalVelocityConstraintCppAd.cpp │ │ │ └── ZeroVelocityConstraintCppAd.cpp │ │ ├── cost │ │ │ ├── CentroidalMpcEndEffectorFootCost.cpp │ │ │ └── ICPCost.cpp │ │ ├── dynamics │ │ │ └── CentroidalDynamicsAD.cpp │ │ ├── initialization │ │ │ └── CentroidalWeightCompInitializer.cpp │ │ └── mrt │ │ │ └── CentroidalMpcMrtJointController.cpp │ └── test │ │ ├── testCentroidalConversions.cpp │ │ ├── testDynamicsHelperFunctions.cpp │ │ └── testPinocchioFrameConversions.cpp ├── humanoid_centroidal_mpc_ros2 │ ├── CMakeLists.txt │ ├── include │ │ └── humanoid_centroidal_mpc_ros2 │ │ │ └── gains │ │ │ ├── EndEffectorFootGainsUpdater.h │ │ │ ├── EndEffectorKinematicsGainsUpdater.h │ │ │ ├── FootCollisionGainsUpdater.h │ │ │ ├── GainsReceiver.h │ │ │ ├── GainsUpdaterInterface.h │ │ │ ├── GainsUpdaterUtils.h │ │ │ ├── GenericGuiInterface.h │ │ │ ├── JointLimitsGainsUpdater.h │ │ │ ├── QuadraticStateCostWeightsUpdater.h │ │ │ ├── QuadraticStateInputGainsUpdater.h │ │ │ ├── StateInputConstraintGainsUpdater.h │ │ │ └── StateInputSoftConstraintGainsUpdater.h │ ├── package.xml │ ├── setup.py │ ├── src │ │ ├── CentroidalMpcDummySimNode.cpp │ │ ├── CentroidalMpcKeyboardPoseCommandNode.cpp │ │ ├── CentroidalMpcRobotSim.cpp │ │ ├── CentroidalMpcSqpNode.cpp │ │ └── gains │ │ │ ├── GainsReceiver.cpp │ │ │ └── GainsUpdaterUtils.cpp │ └── test │ │ └── testHumanoidVisualizer.cpp ├── humanoid_centroidal_mpc_test │ ├── CMakeLists.txt │ ├── include │ │ └── humanoid_centroidal_mpc_test │ │ │ └── CentroidalTestingModelInterface.h │ ├── package.xml │ └── src │ │ ├── testCentroidalMpcRobotModel.cpp │ │ ├── testDynamicsHelperFunctions.cpp │ │ └── testPinocchioFrameConversions.cpp ├── humanoid_common_mpc │ ├── CMakeLists.txt │ ├── config │ │ └── command │ │ │ └── gait.info │ ├── include │ │ └── humanoid_common_mpc │ │ │ ├── HumanoidCostConstraintFactory.h │ │ │ ├── HumanoidPreComputation.h │ │ │ ├── command │ │ │ ├── TargetTrajectoriesCalculatorBase.h │ │ │ └── WalkingVelocityCommand.h │ │ │ ├── common │ │ │ ├── ModelSettings.h │ │ │ ├── MpcRobotModelBase.h │ │ │ └── Types.h │ │ │ ├── constraint │ │ │ ├── ContactMomentXYConstraintCppAd.h │ │ │ ├── EndEffectorKinematicsLinearVelConstraint.h │ │ │ ├── EndEffectorKinematicsTwistConstraint.h │ │ │ ├── FootCollisionConstraint.h │ │ │ ├── FrictionForceConeConstraint.h │ │ │ ├── JointLimitsSoftConstraint.h │ │ │ └── ZeroWrenchConstraint.h │ │ │ ├── contact │ │ │ ├── ContactCenterPoint.h │ │ │ ├── ContactPolygon.h │ │ │ ├── ContactRectangle.h │ │ │ └── ContactWrenchMapper.h │ │ │ ├── cost │ │ │ ├── EndEffectorKinematicCostHelpers.h │ │ │ ├── EndEffectorKinematicsQuadraticCost.h │ │ │ ├── ExternalTorqueQuadraticCostAD.h │ │ │ └── StateInputQuadraticCost.h │ │ │ ├── gait │ │ │ ├── Gait.h │ │ │ ├── GaitSchedule.h │ │ │ ├── GaitScheduleUpdater.h │ │ │ ├── ModeSequenceTemplate.h │ │ │ └── MotionPhaseDefinition.h │ │ │ ├── initialization │ │ │ └── WeightCompInitializer.h │ │ │ ├── pinocchio_model │ │ │ ├── DynamicsHelperFunctions.h │ │ │ ├── PinocchioFrameConversions.h │ │ │ ├── createPinocchioModel.h │ │ │ └── pinocchioUtils.h │ │ │ ├── reference_manager │ │ │ ├── BreakFrequencyAlphaFilter.h │ │ │ ├── ProceduralMpcMotionManager.h │ │ │ └── SwitchedModelReferenceManager.h │ │ │ └── swing_foot_planner │ │ │ ├── CubicSpline.h │ │ │ ├── ImpactProximityFactorBase.h │ │ │ ├── SplineCpg.h │ │ │ └── SwingTrajectoryPlanner.h │ ├── package.xml │ ├── src │ │ ├── HumanoidCostConstraintFactory.cpp │ │ ├── HumanoidPreComputation.cpp │ │ ├── command │ │ │ └── TargetTrajectoriesCalculatorBase.cpp │ │ ├── common │ │ │ └── ModelSettings.cpp │ │ ├── constraint │ │ │ ├── ContactMomentXYConstraintCppAd.cpp │ │ │ ├── EndEffectorKinematicsLinearVelConstraint.cpp │ │ │ ├── EndEffectorKinematicsTwistConstraint.cpp │ │ │ ├── FootCollisionConstraint.cpp │ │ │ ├── FrictionForceConeConstraint.cpp │ │ │ ├── JointLimitsSoftConstraint.cpp │ │ │ └── ZeroWrenchConstraint.cpp │ │ ├── contact │ │ │ ├── ContactCenterPoint.cpp │ │ │ ├── ContactPolygon.cpp │ │ │ └── ContactRectangle.cpp │ │ ├── cost │ │ │ ├── EndEffectorKinematicCostHelpers.cpp │ │ │ ├── EndEffectorKinematicsQuadraticCost.cpp │ │ │ ├── ExternalTorqueQuadraticCostAD.cpp │ │ │ └── StateInputQuadraticCost.cpp │ │ ├── gait │ │ │ ├── Gait.cpp │ │ │ ├── GaitSchedule.cpp │ │ │ ├── GaitScheduleUpdater.cpp │ │ │ └── ModeSequenceTemplate.cpp │ │ ├── initialization │ │ │ └── WeightCompInitializer.cpp │ │ ├── pinocchio_model │ │ │ ├── DynamicsHelperFunctions.cpp │ │ │ ├── createPinocchioModel.cpp │ │ │ └── pinocchioUtils.cpp │ │ ├── reference_manager │ │ │ ├── ProceduralMpcMotionManager.cpp │ │ │ └── SwitchedModelReferenceManager.cpp │ │ └── swing_foot_planner │ │ │ ├── CubicSpline.cpp │ │ │ ├── SplineCpg.cpp │ │ │ └── SwingTrajectoryPlanner.cpp │ └── test │ │ └── testEndEffectorKinematicsCostElement.cpp ├── humanoid_common_mpc_pyutils │ ├── README.md │ ├── humanoid_common_mpc_pyutils │ │ ├── __init__.py │ │ ├── mpc_observation_inspector.py │ │ └── mpc_observation_logger.py │ ├── launch │ │ └── mpc_observation_logger.launch.py │ ├── package.xml │ ├── requirements.txt │ ├── resource │ │ └── humanoid_common_mpc_pyutils │ ├── setup.cfg │ ├── setup.py │ └── test │ │ └── test_xbox_controller.py ├── humanoid_common_mpc_ros2 │ ├── CMakeLists.txt │ ├── humanoid_common_mpc_ros2 │ │ ├── __init__.py │ │ └── mpc_launch_config.py │ ├── include │ │ └── humanoid_common_mpc_ros2 │ │ │ ├── benchmarks │ │ │ ├── DdpBenchmarksPublisher.h │ │ │ └── SqpBenchmarksPublisher.h │ │ │ ├── gait │ │ │ ├── GaitKeyboardPublisher.h │ │ │ ├── GaitScheduleUpdaterRos2.h │ │ │ └── ModeSequenceTemplateRos.h │ │ │ ├── ros_comm │ │ │ ├── MRTPolicySubscriber.h │ │ │ ├── Ros2ProceduralMpcMotionManager.h │ │ │ └── VelocityCommandKeyboardPublisher.h │ │ │ └── visualization │ │ │ ├── COMVisualizer.hpp │ │ │ ├── EquivalentContactCornerForcesVisualizer.h │ │ │ ├── HumanoidVisualizer.h │ │ │ └── HumanoidVisualizerRos2Interface.h │ ├── package.xml │ ├── rviz │ │ └── humanoid.rviz │ ├── setup.py │ └── src │ │ ├── HumanoidGaitCommandNode.cpp │ │ ├── MpcKeyboardVelocityCommandNode.cpp │ │ ├── benchmarks │ │ ├── DdpBenchmarksPublisher.cpp │ │ └── SqpBenchmarksPublisher.cpp │ │ ├── gait │ │ ├── GaitKeyboardPublisher.cpp │ │ └── GaitScheduleUpdaterRos2.cpp │ │ ├── ros_comm │ │ ├── MRTPolicySubscriber.cpp │ │ ├── Ros2ProceduralMpcMotionManager.cpp │ │ └── VelocityCommandKeyboardPublisher.cpp │ │ └── visualization │ │ ├── COMVisualizer.cpp │ │ ├── EquivalentContactCornerForcesVisualizer.cpp │ │ ├── HumanoidVisualizer.cpp │ │ └── HumanoidVisualizerRos2Interface.cpp ├── humanoid_mpc_msgs │ ├── CMakeLists.txt │ ├── msg │ │ └── WalkingVelocityCommand.idl │ └── package.xml ├── humanoid_wb_mpc │ ├── CMakeLists.txt │ ├── include │ │ └── humanoid_wb_mpc │ │ │ ├── WBMpcInterface.h │ │ │ ├── WBMpcPreComputation.h │ │ │ ├── command │ │ │ └── WBMpcTargetTrajectoriesCalculator.h │ │ │ ├── common │ │ │ ├── WBAccelMpcRobotModel.h │ │ │ └── WBAccelPinocchioStateInputMapping.h │ │ │ ├── constraint │ │ │ ├── EndEffectorDynamicsAccelerationsConstraint.h │ │ │ ├── EndEffectorDynamicsLinearAccConstraint.h │ │ │ ├── JointMimicDynamicsConstraint.h │ │ │ ├── SwingLegVerticalConstraintCppAd.h │ │ │ └── ZeroAccelerationConstraintCppAd.h │ │ │ ├── cost │ │ │ ├── EndEffectorDynamicsCostHelpers.h │ │ │ ├── EndEffectorDynamicsFootCost.h │ │ │ ├── EndEffectorDynamicsQuadraticCost.h │ │ │ └── JointTorqueCostCppAd.h │ │ │ ├── dynamics │ │ │ ├── DynamicsHelperFunctions.h │ │ │ └── WBAccelDynamicsAD.h │ │ │ ├── end_effector │ │ │ ├── EndEffectorDynamics.h │ │ │ └── PinocchioEndEffectorDynamicsCppAd.h │ │ │ └── mrt │ │ │ └── WBMpcMrtJointController.h │ ├── package.xml │ └── src │ │ ├── WBMpcInterface.cpp │ │ ├── WBMpcPreComputation.cpp │ │ ├── command │ │ └── WBMpcTargetTrajectoriesCalculator.cpp │ │ ├── constraint │ │ ├── EndEffectorDynamicsAccelerationsConstraint.cpp │ │ ├── EndEffectorDynamicsLinearAccConstraint.cpp │ │ ├── JointMimicDynamicsConstraint.cpp │ │ ├── SwingLegVerticalConstraintCppAd.cpp │ │ └── ZeroAccelerationConstraintCppAd.cpp │ │ ├── cost │ │ ├── EndEffectorDynamicsCostHelpers.cpp │ │ ├── EndEffectorDynamicsFootCost.cpp │ │ ├── EndEffectorDynamicsQuadraticCost.cpp │ │ └── JointTorqueCostCppAd.cpp │ │ ├── dynamics │ │ ├── DynamicsHelperFunctions.cpp │ │ └── WBAccelDynamicsAD.cpp │ │ ├── end_effector │ │ └── PinocchioEndEffectorDynamicsCppAd.cpp │ │ └── mrt │ │ └── WBMpcMrtJointController.cpp ├── humanoid_wb_mpc_ros2 │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ │ ├── WBMpcDummySimNode.cpp │ │ ├── WBMpcPoseCommandNode.cpp │ │ ├── WBMpcRobotSim.cpp │ │ └── WBMpcSqpNode.cpp └── remote_control │ ├── README.md │ ├── launch │ └── xbox_velocity_publisher.launch.py │ ├── package.xml │ ├── remote_control │ ├── __init__.py │ ├── base_velocity_controller_gui.py │ ├── keyboard_walking_command_publisher.py │ ├── tk_app │ │ ├── __init__.py │ │ ├── joystick_gui.py │ │ └── led_indicator_gui.py │ ├── xbox_controller_interface.py │ └── xbox_walking_command_publisher.py │ ├── requirements.txt │ ├── resource │ └── remote_control │ ├── setup.cfg │ ├── setup.py │ └── test │ └── test_xbox_controller.py ├── lib └── mujoco_vendor │ ├── CMakeLists.txt │ ├── README.md │ └── package.xml ├── robot_models └── unitree_g1 │ ├── g1_centroidal_mpc │ ├── CMakeLists.txt │ ├── config │ │ ├── command │ │ │ └── reference.info │ │ └── mpc │ │ │ └── task.info │ ├── launch │ │ ├── dummy_sim.launch.py │ │ ├── dummy_sim_headless.launch.py │ │ ├── mujoco_sim.launch.py │ │ ├── remote-control-dummy-rviz.launch.py │ │ ├── test_visualizer.launch.py │ │ └── visualize.launch.py │ ├── package.xml │ └── test │ │ └── testPinocchioModel.cpp │ ├── g1_description │ ├── CMakeLists.txt │ ├── README.md │ ├── images │ │ └── g1_29dof.png │ ├── launch │ │ └── display.launch.py │ ├── meshes │ │ ├── head_link.STL │ │ ├── left_ankle_pitch_link.STL │ │ ├── left_ankle_roll_link.STL │ │ ├── left_elbow_link.STL │ │ ├── left_hand_index_0_link.STL │ │ ├── left_hand_index_1_link.STL │ │ ├── left_hand_middle_0_link.STL │ │ ├── left_hand_middle_1_link.STL │ │ ├── left_hand_palm_link.STL │ │ ├── left_hand_thumb_0_link.STL │ │ ├── left_hand_thumb_1_link.STL │ │ ├── left_hand_thumb_2_link.STL │ │ ├── left_hip_pitch_link.STL │ │ ├── left_hip_roll_link.STL │ │ ├── left_hip_yaw_link.STL │ │ ├── left_knee_link.STL │ │ ├── left_rubber_hand.STL │ │ ├── left_shoulder_pitch_link.STL │ │ ├── left_shoulder_roll_link.STL │ │ ├── left_shoulder_yaw_link.STL │ │ ├── left_wrist_pitch_link.STL │ │ ├── left_wrist_roll_link.STL │ │ ├── left_wrist_roll_rubber_hand.STL │ │ ├── left_wrist_yaw_link.STL │ │ ├── logo_link.STL │ │ ├── pelvis.STL │ │ ├── pelvis_contour_link.STL │ │ ├── right_ankle_pitch_link.STL │ │ ├── right_ankle_roll_link.STL │ │ ├── right_elbow_link.STL │ │ ├── right_hand_index_0_link.STL │ │ ├── right_hand_index_1_link.STL │ │ ├── right_hand_middle_0_link.STL │ │ ├── right_hand_middle_1_link.STL │ │ ├── right_hand_palm_link.STL │ │ ├── right_hand_thumb_0_link.STL │ │ ├── right_hand_thumb_1_link.STL │ │ ├── right_hand_thumb_2_link.STL │ │ ├── right_hip_pitch_link.STL │ │ ├── right_hip_roll_link.STL │ │ ├── right_hip_yaw_link.STL │ │ ├── right_knee_link.STL │ │ ├── right_rubber_hand.STL │ │ ├── right_shoulder_pitch_link.STL │ │ ├── right_shoulder_roll_link.STL │ │ ├── right_shoulder_yaw_link.STL │ │ ├── right_wrist_pitch_link.STL │ │ ├── right_wrist_roll_link.STL │ │ ├── right_wrist_roll_rubber_hand.STL │ │ ├── right_wrist_yaw_link.STL │ │ ├── torso_constraint_L_link.STL │ │ ├── torso_constraint_L_rod_link.STL │ │ ├── torso_constraint_R_link.STL │ │ ├── torso_constraint_R_rod_link.STL │ │ ├── torso_link.STL │ │ ├── torso_link_23dof_rev_1_0.STL │ │ ├── torso_link_rev_1_0.STL │ │ ├── waist_constraint_L.STL │ │ ├── waist_constraint_R.STL │ │ ├── waist_roll_link.STL │ │ ├── waist_roll_link_rev_1_0.STL │ │ ├── waist_support_link.STL │ │ ├── waist_yaw_link.STL │ │ └── waist_yaw_link_rev_1_0.STL │ ├── package.xml │ ├── rviz │ │ └── urdf_config.rviz │ └── urdf │ │ ├── g1_29dof.urdf │ │ └── g1_29dof.xml │ └── g1_wb_mpc │ ├── CMakeLists.txt │ ├── config │ ├── command │ │ └── reference.info │ └── mpc │ │ └── task.info │ ├── launch │ ├── dummy_sim.launch.py │ ├── mujoco_sim.launch.py │ └── wb_dummy_sim.launch.py │ └── package.xml └── robot_runtime ├── mujoco_sim_interface ├── CMakeLists.txt ├── Readme.md ├── exe │ └── mujocoSimNoTorques.cpp ├── include │ └── mujoco_sim_interface │ │ ├── MujocoRenderer.h │ │ ├── MujocoSimInterface.h │ │ └── MujocoUtils.h ├── package.xml └── src │ ├── MujocoRenderer.cpp │ └── MujocoSimInterface.cpp ├── robot_core ├── CMakeLists.txt ├── include │ └── robot_core │ │ ├── FPSTracker.h │ │ ├── ThreadSafe.h │ │ └── Types.h └── package.xml └── robot_model ├── CMakeLists.txt ├── include └── robot_model │ ├── ControllerBase.h │ ├── IDMapBase.h │ ├── JointIDMap.h │ ├── RobotDescription.h │ ├── RobotHWInterfaceBase.h │ ├── RobotJointAction.h │ └── RobotState.h ├── package.xml ├── src ├── RobotDescription.cpp └── RobotState.cpp └── test └── testRobotDescription.cpp /.clang-format: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/.clang-format -------------------------------------------------------------------------------- /.devcontainer/devcontainer.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/.devcontainer/devcontainer.json -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/bug_report.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/.github/ISSUE_TEMPLATE/bug_report.md -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/feature_request.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/.github/ISSUE_TEMPLATE/feature_request.md -------------------------------------------------------------------------------- /.github/workflows/build_test.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/.github/workflows/build_test.yml -------------------------------------------------------------------------------- /.github/workflows/format_test.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/.github/workflows/format_test.yml -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/.gitignore -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/.gitmodules -------------------------------------------------------------------------------- /CODE_OF_CONDUCT.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/CODE_OF_CONDUCT.md -------------------------------------------------------------------------------- /LICENCE.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/LICENCE.txt -------------------------------------------------------------------------------- /Makefile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/Makefile -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/README.md -------------------------------------------------------------------------------- /dependencies.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/dependencies.txt -------------------------------------------------------------------------------- /docker/Dockerfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/docker/Dockerfile -------------------------------------------------------------------------------- /docker/image_build.bash: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/docker/image_build.bash -------------------------------------------------------------------------------- /docker/launch_wb_mpc.bash: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/docker/launch_wb_mpc.bash -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/CMakeLists.txt -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/CentroidalMpcInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/CentroidalMpcInterface.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/command/CentroidalMpcTargetTrajectoriesCalculator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/command/CentroidalMpcTargetTrajectoriesCalculator.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/common/CentroidalMpcRobotModel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/common/CentroidalMpcRobotModel.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/constraint/JointMimicKinematicConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/constraint/JointMimicKinematicConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/constraint/NormalVelocityConstraintCppAd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/constraint/NormalVelocityConstraintCppAd.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/constraint/ZeroVelocityConstraintCppAd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/constraint/ZeroVelocityConstraintCppAd.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/cost/CentroidalMpcEndEffectorFootCost.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/cost/CentroidalMpcEndEffectorFootCost.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/cost/ICPCost.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/cost/ICPCost.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/dynamics/CentroidalDynamicsAD.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/dynamics/CentroidalDynamicsAD.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/dynamics/DynamicsHelperFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/dynamics/DynamicsHelperFunctions.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/initialization/CentroidalWeightCompInitializer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/initialization/CentroidalWeightCompInitializer.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/mrt/CentroidalMpcMrtJointController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/mrt/CentroidalMpcMrtJointController.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/test/CentroidalTestingModelInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/include/humanoid_centroidal_mpc/test/CentroidalTestingModelInterface.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/CentroidalMpcInterface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/CentroidalMpcInterface.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/command/CentroidalMpcTargetTrajectoriesCalculator.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/command/CentroidalMpcTargetTrajectoriesCalculator.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/constraint/JointMimicKinematicConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/constraint/JointMimicKinematicConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/constraint/NormalVelocityConstraintCppAd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/constraint/NormalVelocityConstraintCppAd.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/constraint/ZeroVelocityConstraintCppAd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/constraint/ZeroVelocityConstraintCppAd.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/cost/CentroidalMpcEndEffectorFootCost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/cost/CentroidalMpcEndEffectorFootCost.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/cost/ICPCost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/cost/ICPCost.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/dynamics/CentroidalDynamicsAD.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/dynamics/CentroidalDynamicsAD.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/initialization/CentroidalWeightCompInitializer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/initialization/CentroidalWeightCompInitializer.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/src/mrt/CentroidalMpcMrtJointController.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/src/mrt/CentroidalMpcMrtJointController.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/test/testCentroidalConversions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/test/testCentroidalConversions.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/test/testDynamicsHelperFunctions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/test/testDynamicsHelperFunctions.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc/test/testPinocchioFrameConversions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc/test/testPinocchioFrameConversions.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/CMakeLists.txt -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/EndEffectorFootGainsUpdater.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/EndEffectorFootGainsUpdater.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/EndEffectorKinematicsGainsUpdater.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/EndEffectorKinematicsGainsUpdater.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/FootCollisionGainsUpdater.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/FootCollisionGainsUpdater.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/GainsReceiver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/GainsReceiver.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/GainsUpdaterInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/GainsUpdaterInterface.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/GainsUpdaterUtils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/GainsUpdaterUtils.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/GenericGuiInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/GenericGuiInterface.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/JointLimitsGainsUpdater.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/JointLimitsGainsUpdater.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/QuadraticStateCostWeightsUpdater.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/QuadraticStateCostWeightsUpdater.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/QuadraticStateInputGainsUpdater.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/QuadraticStateInputGainsUpdater.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/StateInputConstraintGainsUpdater.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/StateInputConstraintGainsUpdater.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/StateInputSoftConstraintGainsUpdater.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/include/humanoid_centroidal_mpc_ros2/gains/StateInputSoftConstraintGainsUpdater.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/setup.py -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/CentroidalMpcDummySimNode.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/CentroidalMpcDummySimNode.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/CentroidalMpcKeyboardPoseCommandNode.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/CentroidalMpcKeyboardPoseCommandNode.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/CentroidalMpcRobotSim.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/CentroidalMpcRobotSim.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/CentroidalMpcSqpNode.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/CentroidalMpcSqpNode.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/gains/GainsReceiver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/gains/GainsReceiver.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/gains/GainsUpdaterUtils.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/src/gains/GainsUpdaterUtils.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_ros2/test/testHumanoidVisualizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_ros2/test/testHumanoidVisualizer.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_test/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_test/CMakeLists.txt -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_test/include/humanoid_centroidal_mpc_test/CentroidalTestingModelInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_test/include/humanoid_centroidal_mpc_test/CentroidalTestingModelInterface.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_test/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_test/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_test/src/testCentroidalMpcRobotModel.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_test/src/testCentroidalMpcRobotModel.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_test/src/testDynamicsHelperFunctions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_test/src/testDynamicsHelperFunctions.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_centroidal_mpc_test/src/testPinocchioFrameConversions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_centroidal_mpc_test/src/testPinocchioFrameConversions.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/CMakeLists.txt -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/config/command/gait.info: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/config/command/gait.info -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/HumanoidCostConstraintFactory.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/HumanoidCostConstraintFactory.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/HumanoidPreComputation.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/HumanoidPreComputation.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/command/TargetTrajectoriesCalculatorBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/command/TargetTrajectoriesCalculatorBase.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/command/WalkingVelocityCommand.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/command/WalkingVelocityCommand.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/common/ModelSettings.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/common/ModelSettings.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/common/MpcRobotModelBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/common/MpcRobotModelBase.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/common/Types.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/common/Types.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/ContactMomentXYConstraintCppAd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/ContactMomentXYConstraintCppAd.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/EndEffectorKinematicsLinearVelConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/EndEffectorKinematicsLinearVelConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/EndEffectorKinematicsTwistConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/EndEffectorKinematicsTwistConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/FootCollisionConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/FootCollisionConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/FrictionForceConeConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/FrictionForceConeConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/JointLimitsSoftConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/JointLimitsSoftConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/ZeroWrenchConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/constraint/ZeroWrenchConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/contact/ContactCenterPoint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/contact/ContactCenterPoint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/contact/ContactPolygon.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/contact/ContactPolygon.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/contact/ContactRectangle.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/contact/ContactRectangle.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/contact/ContactWrenchMapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/contact/ContactWrenchMapper.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/cost/EndEffectorKinematicCostHelpers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/cost/EndEffectorKinematicCostHelpers.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/cost/EndEffectorKinematicsQuadraticCost.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/cost/EndEffectorKinematicsQuadraticCost.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/cost/ExternalTorqueQuadraticCostAD.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/cost/ExternalTorqueQuadraticCostAD.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/cost/StateInputQuadraticCost.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/cost/StateInputQuadraticCost.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/Gait.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/Gait.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/GaitSchedule.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/GaitSchedule.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/GaitScheduleUpdater.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/GaitScheduleUpdater.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/ModeSequenceTemplate.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/ModeSequenceTemplate.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/MotionPhaseDefinition.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/gait/MotionPhaseDefinition.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/initialization/WeightCompInitializer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/initialization/WeightCompInitializer.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/pinocchio_model/DynamicsHelperFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/pinocchio_model/DynamicsHelperFunctions.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/pinocchio_model/PinocchioFrameConversions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/pinocchio_model/PinocchioFrameConversions.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/pinocchio_model/createPinocchioModel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/pinocchio_model/createPinocchioModel.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/pinocchio_model/pinocchioUtils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/pinocchio_model/pinocchioUtils.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/reference_manager/BreakFrequencyAlphaFilter.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/reference_manager/BreakFrequencyAlphaFilter.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/reference_manager/ProceduralMpcMotionManager.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/reference_manager/ProceduralMpcMotionManager.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/reference_manager/SwitchedModelReferenceManager.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/reference_manager/SwitchedModelReferenceManager.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/swing_foot_planner/CubicSpline.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/swing_foot_planner/CubicSpline.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/swing_foot_planner/ImpactProximityFactorBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/swing_foot_planner/ImpactProximityFactorBase.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/swing_foot_planner/SplineCpg.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/swing_foot_planner/SplineCpg.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/swing_foot_planner/SwingTrajectoryPlanner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/include/humanoid_common_mpc/swing_foot_planner/SwingTrajectoryPlanner.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/HumanoidCostConstraintFactory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/HumanoidCostConstraintFactory.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/HumanoidPreComputation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/HumanoidPreComputation.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/command/TargetTrajectoriesCalculatorBase.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/command/TargetTrajectoriesCalculatorBase.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/common/ModelSettings.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/common/ModelSettings.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/constraint/ContactMomentXYConstraintCppAd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/constraint/ContactMomentXYConstraintCppAd.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/constraint/EndEffectorKinematicsLinearVelConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/constraint/EndEffectorKinematicsLinearVelConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/constraint/EndEffectorKinematicsTwistConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/constraint/EndEffectorKinematicsTwistConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/constraint/FootCollisionConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/constraint/FootCollisionConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/constraint/FrictionForceConeConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/constraint/FrictionForceConeConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/constraint/JointLimitsSoftConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/constraint/JointLimitsSoftConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/constraint/ZeroWrenchConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/constraint/ZeroWrenchConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/contact/ContactCenterPoint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/contact/ContactCenterPoint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/contact/ContactPolygon.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/contact/ContactPolygon.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/contact/ContactRectangle.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/contact/ContactRectangle.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/cost/EndEffectorKinematicCostHelpers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/cost/EndEffectorKinematicCostHelpers.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/cost/EndEffectorKinematicsQuadraticCost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/cost/EndEffectorKinematicsQuadraticCost.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/cost/ExternalTorqueQuadraticCostAD.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/cost/ExternalTorqueQuadraticCostAD.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/cost/StateInputQuadraticCost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/cost/StateInputQuadraticCost.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/gait/Gait.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/gait/Gait.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/gait/GaitSchedule.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/gait/GaitSchedule.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/gait/GaitScheduleUpdater.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/gait/GaitScheduleUpdater.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/gait/ModeSequenceTemplate.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/gait/ModeSequenceTemplate.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/initialization/WeightCompInitializer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/initialization/WeightCompInitializer.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/pinocchio_model/DynamicsHelperFunctions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/pinocchio_model/DynamicsHelperFunctions.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/pinocchio_model/createPinocchioModel.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/pinocchio_model/createPinocchioModel.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/pinocchio_model/pinocchioUtils.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/pinocchio_model/pinocchioUtils.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/reference_manager/ProceduralMpcMotionManager.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/reference_manager/ProceduralMpcMotionManager.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/reference_manager/SwitchedModelReferenceManager.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/reference_manager/SwitchedModelReferenceManager.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/swing_foot_planner/CubicSpline.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/swing_foot_planner/CubicSpline.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/swing_foot_planner/SplineCpg.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/swing_foot_planner/SplineCpg.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/src/swing_foot_planner/SwingTrajectoryPlanner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/src/swing_foot_planner/SwingTrajectoryPlanner.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc/test/testEndEffectorKinematicsCostElement.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc/test/testEndEffectorKinematicsCostElement.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/README.md: -------------------------------------------------------------------------------- 1 | Install the xpad driver: https://github.com/paroj/xpad -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/humanoid_common_mpc_pyutils/__init__.py: -------------------------------------------------------------------------------- 1 | from . import mpc_observation_logger 2 | -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/humanoid_common_mpc_pyutils/mpc_observation_inspector.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_pyutils/humanoid_common_mpc_pyutils/mpc_observation_inspector.py -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/humanoid_common_mpc_pyutils/mpc_observation_logger.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_pyutils/humanoid_common_mpc_pyutils/mpc_observation_logger.py -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/launch/mpc_observation_logger.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_pyutils/launch/mpc_observation_logger.launch.py -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_pyutils/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/requirements.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_pyutils/requirements.txt -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/resource/humanoid_common_mpc_pyutils: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/setup.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_pyutils/setup.cfg -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_pyutils/setup.py -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_pyutils/test/test_xbox_controller.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_pyutils/test/test_xbox_controller.py -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/CMakeLists.txt -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/humanoid_common_mpc_ros2/__init__.py: -------------------------------------------------------------------------------- 1 | from . import mpc_launch_config 2 | -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/humanoid_common_mpc_ros2/mpc_launch_config.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/humanoid_common_mpc_ros2/mpc_launch_config.py -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/benchmarks/DdpBenchmarksPublisher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/benchmarks/DdpBenchmarksPublisher.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/benchmarks/SqpBenchmarksPublisher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/benchmarks/SqpBenchmarksPublisher.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/gait/GaitKeyboardPublisher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/gait/GaitKeyboardPublisher.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/gait/GaitScheduleUpdaterRos2.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/gait/GaitScheduleUpdaterRos2.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/gait/ModeSequenceTemplateRos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/gait/ModeSequenceTemplateRos.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/ros_comm/MRTPolicySubscriber.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/ros_comm/MRTPolicySubscriber.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/ros_comm/Ros2ProceduralMpcMotionManager.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/ros_comm/Ros2ProceduralMpcMotionManager.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/ros_comm/VelocityCommandKeyboardPublisher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/ros_comm/VelocityCommandKeyboardPublisher.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/visualization/COMVisualizer.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/visualization/COMVisualizer.hpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/visualization/EquivalentContactCornerForcesVisualizer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/visualization/EquivalentContactCornerForcesVisualizer.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/visualization/HumanoidVisualizer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/visualization/HumanoidVisualizer.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/visualization/HumanoidVisualizerRos2Interface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/include/humanoid_common_mpc_ros2/visualization/HumanoidVisualizerRos2Interface.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/rviz/humanoid.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/rviz/humanoid.rviz -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/setup.py -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/HumanoidGaitCommandNode.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/HumanoidGaitCommandNode.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/MpcKeyboardVelocityCommandNode.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/MpcKeyboardVelocityCommandNode.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/benchmarks/DdpBenchmarksPublisher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/benchmarks/DdpBenchmarksPublisher.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/benchmarks/SqpBenchmarksPublisher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/benchmarks/SqpBenchmarksPublisher.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/gait/GaitKeyboardPublisher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/gait/GaitKeyboardPublisher.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/gait/GaitScheduleUpdaterRos2.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/gait/GaitScheduleUpdaterRos2.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/ros_comm/MRTPolicySubscriber.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/ros_comm/MRTPolicySubscriber.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/ros_comm/Ros2ProceduralMpcMotionManager.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/ros_comm/Ros2ProceduralMpcMotionManager.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/ros_comm/VelocityCommandKeyboardPublisher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/ros_comm/VelocityCommandKeyboardPublisher.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/visualization/COMVisualizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/visualization/COMVisualizer.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/visualization/EquivalentContactCornerForcesVisualizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/visualization/EquivalentContactCornerForcesVisualizer.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/visualization/HumanoidVisualizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/visualization/HumanoidVisualizer.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_common_mpc_ros2/src/visualization/HumanoidVisualizerRos2Interface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_common_mpc_ros2/src/visualization/HumanoidVisualizerRos2Interface.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_mpc_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_mpc_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_mpc_msgs/msg/WalkingVelocityCommand.idl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_mpc_msgs/msg/WalkingVelocityCommand.idl -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_mpc_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_mpc_msgs/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/CMakeLists.txt -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/WBMpcInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/WBMpcInterface.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/WBMpcPreComputation.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/WBMpcPreComputation.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/command/WBMpcTargetTrajectoriesCalculator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/command/WBMpcTargetTrajectoriesCalculator.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/common/WBAccelMpcRobotModel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/common/WBAccelMpcRobotModel.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/common/WBAccelPinocchioStateInputMapping.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/common/WBAccelPinocchioStateInputMapping.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/EndEffectorDynamicsAccelerationsConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/EndEffectorDynamicsAccelerationsConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/EndEffectorDynamicsLinearAccConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/EndEffectorDynamicsLinearAccConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/JointMimicDynamicsConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/JointMimicDynamicsConstraint.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/SwingLegVerticalConstraintCppAd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/SwingLegVerticalConstraintCppAd.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/ZeroAccelerationConstraintCppAd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/constraint/ZeroAccelerationConstraintCppAd.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/cost/EndEffectorDynamicsCostHelpers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/cost/EndEffectorDynamicsCostHelpers.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/cost/EndEffectorDynamicsFootCost.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/cost/EndEffectorDynamicsFootCost.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/cost/EndEffectorDynamicsQuadraticCost.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/cost/EndEffectorDynamicsQuadraticCost.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/cost/JointTorqueCostCppAd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/cost/JointTorqueCostCppAd.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/dynamics/DynamicsHelperFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/dynamics/DynamicsHelperFunctions.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/dynamics/WBAccelDynamicsAD.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/dynamics/WBAccelDynamicsAD.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/end_effector/EndEffectorDynamics.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/end_effector/EndEffectorDynamics.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/end_effector/PinocchioEndEffectorDynamicsCppAd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/end_effector/PinocchioEndEffectorDynamicsCppAd.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/mrt/WBMpcMrtJointController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/include/humanoid_wb_mpc/mrt/WBMpcMrtJointController.h -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/WBMpcInterface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/WBMpcInterface.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/WBMpcPreComputation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/WBMpcPreComputation.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/command/WBMpcTargetTrajectoriesCalculator.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/command/WBMpcTargetTrajectoriesCalculator.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/constraint/EndEffectorDynamicsAccelerationsConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/constraint/EndEffectorDynamicsAccelerationsConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/constraint/EndEffectorDynamicsLinearAccConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/constraint/EndEffectorDynamicsLinearAccConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/constraint/JointMimicDynamicsConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/constraint/JointMimicDynamicsConstraint.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/constraint/SwingLegVerticalConstraintCppAd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/constraint/SwingLegVerticalConstraintCppAd.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/constraint/ZeroAccelerationConstraintCppAd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/constraint/ZeroAccelerationConstraintCppAd.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/cost/EndEffectorDynamicsCostHelpers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/cost/EndEffectorDynamicsCostHelpers.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/cost/EndEffectorDynamicsFootCost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/cost/EndEffectorDynamicsFootCost.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/cost/EndEffectorDynamicsQuadraticCost.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/cost/EndEffectorDynamicsQuadraticCost.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/cost/JointTorqueCostCppAd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/cost/JointTorqueCostCppAd.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/dynamics/DynamicsHelperFunctions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/dynamics/DynamicsHelperFunctions.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/dynamics/WBAccelDynamicsAD.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/dynamics/WBAccelDynamicsAD.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/end_effector/PinocchioEndEffectorDynamicsCppAd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/end_effector/PinocchioEndEffectorDynamicsCppAd.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc/src/mrt/WBMpcMrtJointController.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc/src/mrt/WBMpcMrtJointController.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc_ros2/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc_ros2/CMakeLists.txt -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc_ros2/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc_ros2/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc_ros2/src/WBMpcDummySimNode.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc_ros2/src/WBMpcDummySimNode.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc_ros2/src/WBMpcPoseCommandNode.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc_ros2/src/WBMpcPoseCommandNode.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc_ros2/src/WBMpcRobotSim.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc_ros2/src/WBMpcRobotSim.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/humanoid_wb_mpc_ros2/src/WBMpcSqpNode.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/humanoid_wb_mpc_ros2/src/WBMpcSqpNode.cpp -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/README.md: -------------------------------------------------------------------------------- 1 | Install the xpad driver: https://github.com/paroj/xpad -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/launch/xbox_velocity_publisher.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/launch/xbox_velocity_publisher.launch.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/package.xml -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/remote_control/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/remote_control/__init__.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/remote_control/base_velocity_controller_gui.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/remote_control/base_velocity_controller_gui.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/remote_control/keyboard_walking_command_publisher.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/remote_control/keyboard_walking_command_publisher.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/remote_control/tk_app/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/remote_control/tk_app/__init__.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/remote_control/tk_app/joystick_gui.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/remote_control/tk_app/joystick_gui.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/remote_control/tk_app/led_indicator_gui.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/remote_control/tk_app/led_indicator_gui.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/remote_control/xbox_controller_interface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/remote_control/xbox_controller_interface.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/remote_control/xbox_walking_command_publisher.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/remote_control/xbox_walking_command_publisher.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/requirements.txt: -------------------------------------------------------------------------------- 1 | pygame>=2.5.2 2 | customtkinter>=5.2.2 -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/resource/remote_control: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/setup.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/setup.cfg -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/setup.py -------------------------------------------------------------------------------- /humanoid_nmpc/remote_control/test/test_xbox_controller.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/humanoid_nmpc/remote_control/test/test_xbox_controller.py -------------------------------------------------------------------------------- /lib/mujoco_vendor/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/lib/mujoco_vendor/CMakeLists.txt -------------------------------------------------------------------------------- /lib/mujoco_vendor/README.md: -------------------------------------------------------------------------------- 1 | # MuJoCo vendor package -------------------------------------------------------------------------------- /lib/mujoco_vendor/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/lib/mujoco_vendor/package.xml -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/CMakeLists.txt -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/config/command/reference.info: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/config/command/reference.info -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/config/mpc/task.info: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/config/mpc/task.info -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/launch/dummy_sim.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/launch/dummy_sim.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/launch/dummy_sim_headless.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/launch/dummy_sim_headless.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/launch/mujoco_sim.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/launch/mujoco_sim.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/launch/remote-control-dummy-rviz.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/launch/remote-control-dummy-rviz.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/launch/test_visualizer.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/launch/test_visualizer.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/launch/visualize.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/launch/visualize.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/package.xml -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_centroidal_mpc/test/testPinocchioModel.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_centroidal_mpc/test/testPinocchioModel.cpp -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/CMakeLists.txt -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/README.md -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/images/g1_29dof.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/images/g1_29dof.png -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/launch/display.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/launch/display.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/head_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/head_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_ankle_pitch_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_ankle_pitch_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_ankle_roll_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_ankle_roll_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_elbow_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_elbow_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hand_index_0_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hand_index_0_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hand_index_1_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hand_index_1_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hand_middle_0_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hand_middle_0_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hand_middle_1_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hand_middle_1_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hand_palm_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hand_palm_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hand_thumb_0_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hand_thumb_0_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hand_thumb_1_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hand_thumb_1_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hand_thumb_2_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hand_thumb_2_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hip_pitch_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hip_pitch_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hip_roll_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hip_roll_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_hip_yaw_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_hip_yaw_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_knee_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_knee_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_rubber_hand.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_rubber_hand.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_shoulder_pitch_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_shoulder_pitch_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_shoulder_roll_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_shoulder_roll_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_shoulder_yaw_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_shoulder_yaw_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_wrist_pitch_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_wrist_pitch_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_wrist_roll_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_wrist_roll_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_wrist_roll_rubber_hand.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_wrist_roll_rubber_hand.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/left_wrist_yaw_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/left_wrist_yaw_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/logo_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/logo_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/pelvis.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/pelvis.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/pelvis_contour_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/pelvis_contour_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_ankle_pitch_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_ankle_pitch_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_ankle_roll_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_ankle_roll_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_elbow_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_elbow_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hand_index_0_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hand_index_0_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hand_index_1_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hand_index_1_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hand_middle_0_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hand_middle_0_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hand_middle_1_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hand_middle_1_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hand_palm_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hand_palm_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hand_thumb_0_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hand_thumb_0_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hand_thumb_1_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hand_thumb_1_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hand_thumb_2_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hand_thumb_2_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hip_pitch_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hip_pitch_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hip_roll_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hip_roll_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_hip_yaw_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_hip_yaw_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_knee_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_knee_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_rubber_hand.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_rubber_hand.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_shoulder_pitch_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_shoulder_pitch_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_shoulder_roll_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_shoulder_roll_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_shoulder_yaw_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_shoulder_yaw_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_wrist_pitch_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_wrist_pitch_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_wrist_roll_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_wrist_roll_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_wrist_roll_rubber_hand.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_wrist_roll_rubber_hand.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/right_wrist_yaw_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/right_wrist_yaw_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/torso_constraint_L_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/torso_constraint_L_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/torso_constraint_L_rod_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/torso_constraint_L_rod_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/torso_constraint_R_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/torso_constraint_R_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/torso_constraint_R_rod_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/torso_constraint_R_rod_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/torso_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/torso_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/torso_link_23dof_rev_1_0.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/torso_link_23dof_rev_1_0.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/torso_link_rev_1_0.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/torso_link_rev_1_0.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/waist_constraint_L.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/waist_constraint_L.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/waist_constraint_R.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/waist_constraint_R.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/waist_roll_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/waist_roll_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/waist_roll_link_rev_1_0.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/waist_roll_link_rev_1_0.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/waist_support_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/waist_support_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/waist_yaw_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/waist_yaw_link.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/meshes/waist_yaw_link_rev_1_0.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/meshes/waist_yaw_link_rev_1_0.STL -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/package.xml -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/rviz/urdf_config.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/rviz/urdf_config.rviz -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/urdf/g1_29dof.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/urdf/g1_29dof.urdf -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_description/urdf/g1_29dof.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_description/urdf/g1_29dof.xml -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_wb_mpc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_wb_mpc/CMakeLists.txt -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_wb_mpc/config/command/reference.info: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_wb_mpc/config/command/reference.info -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_wb_mpc/config/mpc/task.info: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_wb_mpc/config/mpc/task.info -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_wb_mpc/launch/dummy_sim.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_wb_mpc/launch/dummy_sim.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_wb_mpc/launch/mujoco_sim.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_wb_mpc/launch/mujoco_sim.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_wb_mpc/launch/wb_dummy_sim.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_wb_mpc/launch/wb_dummy_sim.launch.py -------------------------------------------------------------------------------- /robot_models/unitree_g1/g1_wb_mpc/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_models/unitree_g1/g1_wb_mpc/package.xml -------------------------------------------------------------------------------- /robot_runtime/mujoco_sim_interface/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/mujoco_sim_interface/CMakeLists.txt -------------------------------------------------------------------------------- /robot_runtime/mujoco_sim_interface/Readme.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/mujoco_sim_interface/Readme.md -------------------------------------------------------------------------------- /robot_runtime/mujoco_sim_interface/exe/mujocoSimNoTorques.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/mujoco_sim_interface/exe/mujocoSimNoTorques.cpp -------------------------------------------------------------------------------- /robot_runtime/mujoco_sim_interface/include/mujoco_sim_interface/MujocoRenderer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/mujoco_sim_interface/include/mujoco_sim_interface/MujocoRenderer.h -------------------------------------------------------------------------------- /robot_runtime/mujoco_sim_interface/include/mujoco_sim_interface/MujocoSimInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/mujoco_sim_interface/include/mujoco_sim_interface/MujocoSimInterface.h -------------------------------------------------------------------------------- /robot_runtime/mujoco_sim_interface/include/mujoco_sim_interface/MujocoUtils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/mujoco_sim_interface/include/mujoco_sim_interface/MujocoUtils.h -------------------------------------------------------------------------------- /robot_runtime/mujoco_sim_interface/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/mujoco_sim_interface/package.xml -------------------------------------------------------------------------------- /robot_runtime/mujoco_sim_interface/src/MujocoRenderer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/mujoco_sim_interface/src/MujocoRenderer.cpp -------------------------------------------------------------------------------- /robot_runtime/mujoco_sim_interface/src/MujocoSimInterface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/mujoco_sim_interface/src/MujocoSimInterface.cpp -------------------------------------------------------------------------------- /robot_runtime/robot_core/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_core/CMakeLists.txt -------------------------------------------------------------------------------- /robot_runtime/robot_core/include/robot_core/FPSTracker.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_core/include/robot_core/FPSTracker.h -------------------------------------------------------------------------------- /robot_runtime/robot_core/include/robot_core/ThreadSafe.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_core/include/robot_core/ThreadSafe.h -------------------------------------------------------------------------------- /robot_runtime/robot_core/include/robot_core/Types.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_core/include/robot_core/Types.h -------------------------------------------------------------------------------- /robot_runtime/robot_core/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_core/package.xml -------------------------------------------------------------------------------- /robot_runtime/robot_model/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/CMakeLists.txt -------------------------------------------------------------------------------- /robot_runtime/robot_model/include/robot_model/ControllerBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/include/robot_model/ControllerBase.h -------------------------------------------------------------------------------- /robot_runtime/robot_model/include/robot_model/IDMapBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/include/robot_model/IDMapBase.h -------------------------------------------------------------------------------- /robot_runtime/robot_model/include/robot_model/JointIDMap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/include/robot_model/JointIDMap.h -------------------------------------------------------------------------------- /robot_runtime/robot_model/include/robot_model/RobotDescription.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/include/robot_model/RobotDescription.h -------------------------------------------------------------------------------- /robot_runtime/robot_model/include/robot_model/RobotHWInterfaceBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/include/robot_model/RobotHWInterfaceBase.h -------------------------------------------------------------------------------- /robot_runtime/robot_model/include/robot_model/RobotJointAction.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/include/robot_model/RobotJointAction.h -------------------------------------------------------------------------------- /robot_runtime/robot_model/include/robot_model/RobotState.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/include/robot_model/RobotState.h -------------------------------------------------------------------------------- /robot_runtime/robot_model/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/package.xml -------------------------------------------------------------------------------- /robot_runtime/robot_model/src/RobotDescription.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/src/RobotDescription.cpp -------------------------------------------------------------------------------- /robot_runtime/robot_model/src/RobotState.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/src/RobotState.cpp -------------------------------------------------------------------------------- /robot_runtime/robot_model/test/testRobotDescription.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manumerous/wb_humanoid_mpc/HEAD/robot_runtime/robot_model/test/testRobotDescription.cpp --------------------------------------------------------------------------------