├── .gitignore
├── LICENSE
├── README.assets
└── legged_robot.gif
├── README.md
├── humanoid_controllers
├── CMakeLists.txt
├── config
│ └── controllers.yaml
├── humanoid_controllers_plugins.xml
├── include
│ └── humanoid_controllers
│ │ ├── SafetyChecker.h
│ │ ├── TargetTrajectoriesPublisher.h
│ │ ├── humanoidController.h
│ │ └── visualization
│ │ └── humanoidSelfCollisionVisualization.h
├── launch
│ ├── load_cheat_controller.launch.py
│ ├── load_joy_controller.launch.py
│ └── load_normal_controller.launch.py
├── package.xml
└── src
│ ├── CheatControllerNode.cpp
│ ├── JoyControllerNode.cpp
│ ├── NormalControllerNode.cpp
│ ├── TargetTrajectoriesPublisher.cpp
│ └── humanoidController.cpp
├── humanoid_dummy
├── CMakeLists.txt
├── include
│ └── humanoid_dummy
│ │ ├── gait
│ │ ├── GaitKeyboardPublisher.h
│ │ ├── GaitReceiver.h
│ │ └── ModeSequenceTemplateRos.h
│ │ └── visualization
│ │ └── HumanoidVisualizer.h
├── launch
│ ├── legged_robot_sqp.launch.py
│ └── multiplot.launch.py
├── package.xml
├── rviz
│ └── humanoid.rviz
└── src
│ ├── HumanoidDdpMpcNode.cpp
│ ├── HumanoidDummyNode.cpp
│ ├── HumanoidGaitCommandNode.cpp
│ ├── HumanoidIpmMpcNode.cpp
│ ├── HumanoidPoseCommandNode.cpp
│ ├── HumanoidSqpMpcNode.cpp
│ ├── gait
│ ├── GaitKeyboardPublisher.cpp
│ └── GaitReceiver.cpp
│ └── visualization
│ └── HumanoidVisualizer.cpp
├── humanoid_estimation
├── CMakeLists.txt
├── include
│ └── humanoid_estimation
│ │ ├── FromTopiceEstimate.h
│ │ ├── LinearKalmanFilter.h
│ │ └── StateEstimateBase.h
├── package.xml
└── src
│ ├── FromTopicEstimate.cpp
│ ├── LinearKalmanFilter.cpp
│ └── StateEstimateBase.cpp
├── humanoid_interface
├── CMakeLists.txt
├── auto_generated
│ └── .gitignore
├── config
│ ├── command
│ │ ├── gait.info
│ │ ├── gait_.info
│ │ ├── reference.info
│ │ └── reference_.info
│ ├── mpc
│ │ ├── task.info
│ │ └── task_.info
│ └── multiplot
│ │ ├── friction_cone.xml
│ │ └── zero_velocity.xml
├── include
│ └── humanoid_interface
│ │ ├── HumanoidInterface.h
│ │ ├── HumanoidPreComputation.h
│ │ ├── common
│ │ ├── ModelSettings.h
│ │ ├── Types.h
│ │ └── utils.h
│ │ ├── constraint
│ │ ├── EndEffectorLinearConstraint.h
│ │ ├── FootRollConstraint.h
│ │ ├── FrictionConeConstraint.h
│ │ ├── LeggedSelfCollisionConstraint.h
│ │ ├── NormalVelocityConstraintCppAd.h
│ │ ├── ZeroForceConstraint.h
│ │ └── ZeroVelocityConstraintCppAd.h
│ │ ├── cost
│ │ └── HumanoidQuadraticTrackingCost.h
│ │ ├── dynamics
│ │ └── HumanoidDynamicsAD.h
│ │ ├── foot_planner
│ │ ├── CubicSpline.h
│ │ ├── SplineCpg.h
│ │ └── SwingTrajectoryPlanner.h
│ │ ├── gait
│ │ ├── Gait.h
│ │ ├── GaitSchedule.h
│ │ ├── LegLogic.h
│ │ ├── ModeSequenceTemplate.h
│ │ └── MotionPhaseDefinition.h
│ │ ├── initialization
│ │ └── HumanoidInitializer.h
│ │ ├── package_path.h.in
│ │ └── reference_manager
│ │ └── SwitchedModelReferenceManager.h
├── package.xml
├── src
│ ├── HumanoidInterface.cpp
│ ├── HumanoidPreComputation.cpp
│ ├── common
│ │ └── ModelSettings.cpp
│ ├── constraint
│ │ ├── EndEffectorLinearConstraint.cpp
│ │ ├── FootRollContraint.cpp
│ │ ├── FrictionConeConstraint.cpp
│ │ ├── NormalVelocityConstraintCppAd.cpp
│ │ ├── ZeroForceConstraint.cpp
│ │ └── ZeroVelocityConstraintCppAd.cpp
│ ├── dynamics
│ │ └── HumanoidDynamicsAD.cpp
│ ├── foot_planner
│ │ ├── CubicSpline.cpp
│ │ ├── SplineCpg.cpp
│ │ └── SwingTrajectoryPlanner.cpp
│ ├── gait
│ │ ├── Gait.cpp
│ │ ├── GaitSchedule.cpp
│ │ ├── LegLogic.cpp
│ │ └── ModeSequenceTemplate.cpp
│ ├── initialization
│ │ └── HumanoidInitializer.cpp
│ └── reference_manager
│ │ └── SwitchedModelReferenceManager.cpp
└── test
│ ├── AnymalFactoryFunctions.cpp
│ ├── constraint
│ ├── testEndEffectorLinearConstraint.cpp
│ ├── testFrictionConeConstraint.cpp
│ └── testZeroForceConstraint.cpp
│ └── include
│ └── humanoid_interface
│ └── test
│ └── AnymalFactoryFunctions.h
├── humanoid_legged_description
├── .gitignore
├── CMakeLists.txt
├── config
│ └── joint_names_humanoid_legged.yaml
├── export.log
├── launch
│ ├── visualize.launch.py
│ └── visualize.launch_.py
├── meshes
│ ├── arm_l1_link.STL
│ ├── arm_l2_link.STL
│ ├── arm_l3_link.STL
│ ├── arm_l4_link.STL
│ ├── arm_l5_link.STL
│ ├── arm_l6_link.STL
│ ├── arm_r1_link.STL
│ ├── arm_r2_link.STL
│ ├── arm_r3_link.STL
│ ├── arm_r4_link.STL
│ ├── arm_r5_link.STL
│ ├── arm_r6_link.STL
│ ├── base_link.STL
│ ├── head_yaw_link.STL
│ ├── leg_l1_link.STL
│ ├── leg_l2_link.STL
│ ├── leg_l3_link.STL
│ ├── leg_l4_link.STL
│ ├── leg_l5_link.STL
│ ├── leg_l6_link.STL
│ ├── leg_r1_link.STL
│ ├── leg_r2_link.STL
│ ├── leg_r3_link.STL
│ ├── leg_r4_link.STL
│ ├── leg_r5_link.STL
│ ├── leg_r6_link.STL
│ └── waist_yaw_link.STL
├── mjcf
│ ├── asset
│ │ └── block.png
│ └── humanoid_legged_control_.xml
├── package.xml
├── rviz
│ └── humanoid_legged_control.rviz
└── urdf
│ ├── humanoid_legged_control_.urdf
│ └── humanoid_legged_origin.urdf
├── humanoid_mujoco_sim
├── humanoid_mujoco_sim
│ ├── __init__.py
│ ├── humanoid_sim.py
│ ├── joy.py
│ ├── mujoco_base.py
│ └── teleop.py
├── package.xml
├── resource
│ └── humanoid_mujoco_sim
├── setup.cfg
├── setup.py
└── test
│ ├── test_copyright.py
│ ├── test_flake8.py
│ └── test_pep257.py
├── humanoid_wbc
├── CMakeLists.txt
├── include
│ └── humanoid_wbc
│ │ ├── HierarchicalWbc.h
│ │ ├── HoQp.h
│ │ ├── Task.h
│ │ ├── WbcBase.h
│ │ └── WeightedWbc.h
├── package.xml
├── src
│ ├── HierarchicalWbc.cpp
│ ├── HoQp.cpp
│ ├── WbcBase.cpp
│ └── WeightedWbc.cpp
└── test
│ └── HoQp_test.cpp
└── qpoases_catkin
├── CMakeLists.txt
└── package.xml
/.gitignore:
--------------------------------------------------------------------------------
1 | .idea/
2 | .vscode/
3 | __pycache__/
4 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2025 botianhao
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.assets/legged_robot.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/botianhao/humanoid_control/cfb27eb205d6ee21a801abe273ffc0a53d3be0f2/README.assets/legged_robot.gif
--------------------------------------------------------------------------------
/humanoid_controllers/config/controllers.yaml:
--------------------------------------------------------------------------------
1 | controllers:
2 | joint_state_controller:
3 | type: joint_state_controller/JointStateController
4 | publish_rate: 100
5 | humanoid_controller:
6 | type: humanoid_controller/humanoidController
7 | humanoid_cheater_controller:
8 | type: humanoid_controller/humanoidCheaterController
9 |
--------------------------------------------------------------------------------
/humanoid_controllers/humanoid_controllers_plugins.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
5 |
6 | The basic humanoid controller.
7 |
8 |
9 |
10 |
12 |
13 | The basic humanoid controller with cheat state estimator
14 |
15 |
16 |
17 |
--------------------------------------------------------------------------------
/humanoid_controllers/include/humanoid_controllers/SafetyChecker.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by qiayuan on 2022/7/26.
3 | //
4 |
5 | #pragma once
6 |
7 | #include
8 |
9 | namespace ocs2 {
10 | namespace humanoid {
11 | using namespace centroidal_model;
12 | class SafetyChecker {
13 | public:
14 | explicit SafetyChecker(const CentroidalModelInfo& info) : info_(info) {}
15 |
16 | bool check(const SystemObservation& observation, const vector_t& /*optimized_state*/, const vector_t& /*optimized_input*/) {
17 | return checkOrientation(observation);
18 | }
19 |
20 | protected:
21 | bool checkOrientation(const SystemObservation& observation) {
22 | vector_t pose = getBasePose(observation.state, info_);
23 | if (pose(5) > M_PI_2 || pose(5) < -M_PI_2) {
24 | std::cerr << "[SafetyChecker] Orientation safety check failed!" << std::endl;
25 | //output pose
26 | // std::cerr << "pose: " << pose << std::endl;
27 | return false;
28 | }
29 | return true;
30 | }
31 |
32 | const CentroidalModelInfo& info_;
33 | };
34 |
35 | } // namespace humanoid
36 | } // namespace ocs2
37 |
--------------------------------------------------------------------------------
/humanoid_controllers/include/humanoid_controllers/TargetTrajectoriesPublisher.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by qiayuan on 2022/7/24.
3 | //
4 |
5 | #pragma once
6 |
7 | #include
8 | #include
9 |
10 |
11 | #include
12 | #include
13 | #include
14 | #include
15 |
16 |
17 | #include
18 | #include
19 | #include
20 |
21 | #include
22 | #include "rclcpp/rclcpp.hpp"
23 | #include
24 |
25 | namespace ocs2 {
26 | namespace humanoid {
27 |
28 | class TargetTrajectoriesPublisher final {
29 | public:
30 | using CmdToTargetTrajectories = std::function;
31 |
32 | TargetTrajectoriesPublisher(rclcpp::Node::SharedPtr& node, const std::string& topicPrefix, CmdToTargetTrajectories goalToTargetTrajectories,
33 | CmdToTargetTrajectories cmdVelToTargetTrajectories)
34 | : goalToTargetTrajectories_(std::move(goalToTargetTrajectories)),
35 | cmdVelToTargetTrajectories_(std::move(cmdVelToTargetTrajectories)),
36 | buffer_(node->get_clock()),
37 | tf2_(buffer_) {
38 | // Trajectories publisher
39 | targetTrajectoriesPublisher_.reset(new TargetTrajectoriesRosPublisher(node, topicPrefix));
40 |
41 | // observation subscriber
42 |
43 | observationSub_ = node->create_subscription(topicPrefix + "_mpc_observation", 1, std::bind(&TargetTrajectoriesPublisher::observationCallback, this, std::placeholders::_1));
44 |
45 | // goal subscriber
46 |
47 |
48 | // cmd_vel subscriber
49 |
50 |
51 | goalSub_ = node->create_subscription("/move_base_simple/goal", 1, std::bind(&TargetTrajectoriesPublisher::goalCallback, this, std::placeholders::_1));
52 | cmdVelSub_ = node->create_subscription("/cmd_vel", 1, std::bind(&TargetTrajectoriesPublisher::cmdVelCallback, this, std::placeholders::_1));
53 | }
54 |
55 |
56 | void observationCallback(const ocs2_msgs::msg::MpcObservation::SharedPtr msg){
57 | std::lock_guard lock(latestObservationMutex_);
58 | latestObservation_ = ros_msg_conversions::readObservationMsg(*msg);
59 | }
60 |
61 | void cmdVelCallback(const geometry_msgs::msg::Twist::SharedPtr msg) {
62 | if (latestObservation_.time == 0.0) {
63 | return;
64 | }
65 |
66 | vector_t cmdVel = vector_t::Zero(4);
67 | cmdVel[0] = msg->linear.x;
68 | cmdVel[1] = msg->linear.y;
69 | cmdVel[2] = msg->linear.z;
70 | cmdVel[3] = msg->angular.z;
71 |
72 | const auto trajectories = cmdVelToTargetTrajectories_(cmdVel, latestObservation_);
73 | targetTrajectoriesPublisher_->publishTargetTrajectories(trajectories);
74 | };
75 |
76 | void goalCallback(const geometry_msgs::msg::PoseStamped::SharedPtr msg) {
77 | if (latestObservation_.time == 0.0) {
78 | return;
79 | }
80 | geometry_msgs::msg::PoseStamped pose = *msg;
81 | try {
82 | buffer_.transform(pose, pose, "odom", tf2::durationFromSec(0.2));
83 | } catch (tf2::TransformException& ex) {
84 | printf("Failure %s\n", ex.what());
85 | return;
86 | }
87 |
88 | vector_t cmdGoal = vector_t::Zero(6);
89 | cmdGoal[0] = pose.pose.position.x;
90 | cmdGoal[1] = pose.pose.position.y;
91 | cmdGoal[2] = pose.pose.position.z;
92 | Eigen::Quaternion q(pose.pose.orientation.w, pose.pose.orientation.x, pose.pose.orientation.y, pose.pose.orientation.z);
93 | cmdGoal[3] = q.toRotationMatrix().eulerAngles(0, 1, 2).z();
94 | cmdGoal[4] = q.toRotationMatrix().eulerAngles(0, 1, 2).y();
95 | cmdGoal[5] = q.toRotationMatrix().eulerAngles(0, 1, 2).x();
96 |
97 | const auto trajectories = goalToTargetTrajectories_(cmdGoal, latestObservation_);
98 | targetTrajectoriesPublisher_->publishTargetTrajectories(trajectories);
99 | }
100 | private:
101 | CmdToTargetTrajectories goalToTargetTrajectories_, cmdVelToTargetTrajectories_;
102 |
103 | std::unique_ptr targetTrajectoriesPublisher_;
104 |
105 |
106 |
107 | rclcpp::Subscription::SharedPtr observationSub_;
108 | rclcpp::Subscription::SharedPtr goalSub_;
109 | rclcpp::Subscription::SharedPtr cmdVelSub_;
110 | tf2_ros::Buffer buffer_;
111 | tf2_ros::TransformListener tf2_;
112 |
113 | mutable std::mutex latestObservationMutex_;
114 | SystemObservation latestObservation_;
115 | };
116 |
117 | } // namespace humanoid
118 | } // namespace ocs2
119 |
--------------------------------------------------------------------------------
/humanoid_controllers/include/humanoid_controllers/humanoidController.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by qiayuan on 2022/6/24.
3 | //
4 |
5 | #pragma once
6 |
7 |
8 | #include "rclcpp/rclcpp.hpp"
9 | #include
10 | #include
11 | #include
12 | #include
13 | #include
14 | #include
15 | #include
16 | #include
17 |
18 | #include "humanoid_controllers/SafetyChecker.h"
19 | #include "humanoid_controllers/visualization/humanoidSelfCollisionVisualization.h"
20 |
21 | #include "std_msgs/msg/int8_multi_array.hpp"
22 | #include "std_msgs/msg/float32_multi_array.hpp"
23 | #include "std_msgs/msg/bool.hpp"
24 | #include "sensor_msgs/msg/imu.hpp"
25 |
26 |
27 |
28 | namespace humanoid_controller{
29 | using namespace ocs2;
30 | using namespace humanoid;
31 |
32 | class humanoidController{
33 | public:
34 | humanoidController() = default;
35 | ~humanoidController();
36 | bool init(rclcpp::Node::SharedPtr &controller_nh);
37 | void update(const rclcpp::Time& time, const rclcpp::Duration& period);
38 | void starting(const rclcpp::Time& time);
39 | void stopping(const rclcpp::Time& /*time*/) { mpcRunning_ = false; }
40 |
41 | protected:
42 | virtual void updateStateEstimation(const rclcpp::Time& time, const rclcpp::Duration& period);
43 |
44 | virtual void setupHumanoidInterface(const std::string& taskFile, const std::string& urdfFile, const std::string& referenceFile,
45 | bool verbose);
46 | virtual void setupMpc();
47 | virtual void setupMrt();
48 | virtual void setupStateEstimate(const std::string& taskFile, bool verbose);
49 |
50 | void jointStateCallback(const std_msgs::msg::Float32MultiArray::SharedPtr msg);
51 | void ImuCallback(const sensor_msgs::msg::Imu::SharedPtr msg);
52 | void HwSwitchCallback(const std_msgs::msg::Bool::SharedPtr msg);
53 |
54 | // Interface
55 | std::shared_ptr HumanoidInterface_;
56 | std::shared_ptr eeKinematicsPtr_;
57 |
58 | // State Estimation
59 | SystemObservation currentObservation_;
60 | vector_t measuredRbdState_;
61 | std::shared_ptr stateEstimate_;
62 | std::shared_ptr rbdConversions_;
63 |
64 | // Whole Body Control
65 | std::shared_ptr wbc_;
66 | std::shared_ptr safetyChecker_;
67 |
68 | // Nonlinear MPC
69 | std::shared_ptr mpc_;
70 | std::shared_ptr mpcMrtInterface_;
71 |
72 | // Visualization
73 | std::shared_ptr robotVisualizer_;
74 | rclcpp::Publisher::SharedPtr observationPublisher_;
75 |
76 | //Controller Interface
77 | rclcpp::Publisher::SharedPtr targetTorquePub_;
78 | rclcpp::Publisher::SharedPtr targetPosPub_;
79 | rclcpp::Publisher::SharedPtr targetVelPub_;
80 | rclcpp::Publisher::SharedPtr targetKpPub_;
81 | rclcpp::Publisher::SharedPtr targetKdPub_;
82 |
83 | rclcpp::Publisher::SharedPtr vs_xianyanPub_;
84 | rclcpp::Publisher::SharedPtr vs_basePub_;//估计的足端速度
85 | rclcpp::Publisher::SharedPtr foot_vel_estimatePub_;//估计的足端速度
86 | rclcpp::Publisher::SharedPtr cmd_contactFlagPub_;//命令的接触状态
87 |
88 |
89 | rclcpp::Subscription::SharedPtr jointPosVelSub_;
90 | rclcpp::Subscription::SharedPtr imuSub_;
91 | rclcpp::Subscription::SharedPtr hwSwitchSub_;
92 |
93 | bool hwSwitch_ = false;
94 |
95 | // Node Handle
96 | rclcpp::Node::SharedPtr controllerNh_;
97 |
98 |
99 | private:
100 | std::thread mpcThread_;
101 | std::atomic_bool controllerRunning_{}, mpcRunning_{};
102 | benchmark::RepeatedTimer mpcTimer_;
103 | benchmark::RepeatedTimer wbcTimer_;
104 | size_t jointNum_ = 12;
105 | vector_t jointPos_, jointVel_;
106 | Eigen::Quaternion quat_;
107 | contact_flag_t contactFlag_;
108 | vector3_t angularVel_, linearAccel_;
109 | matrix3_t orientationCovariance_, angularVelCovariance_, linearAccelCovariance_;
110 | size_t plannedMode_ = 3;
111 | vector_t defalutJointPos_;
112 | vector_t joint_pos_bias_;
113 | };
114 |
115 | class humanoidCheaterController : public humanoidController {
116 | protected:
117 | void setupStateEstimate(const std::string& taskFile, bool verbose) override;
118 | };
119 |
120 | } // namespace humanoid_controller
121 |
122 |
--------------------------------------------------------------------------------
/humanoid_controllers/include/humanoid_controllers/visualization/humanoidSelfCollisionVisualization.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by qiayuan on 23-1-30.
3 | //
4 |
5 | #pragma once
6 | #include "rclcpp/rclcpp.hpp"
7 |
8 | #include
9 |
10 | #include
11 |
12 | namespace ocs2 {
13 | namespace humanoid {
14 |
15 |
16 | class humanoidSelfCollisionVisualization : public GeometryInterfaceVisualization {
17 | public:
18 | humanoidSelfCollisionVisualization(PinocchioInterface pinocchioInterface, PinocchioGeometryInterface geometryInterface,
19 | const CentroidalModelPinocchioMapping& mapping, rclcpp::Node::SharedPtr &node, scalar_t maxUpdateFrequency = 50.0)
20 | : mappingPtr_(mapping.clone()),
21 | GeometryInterfaceVisualization(std::move(pinocchioInterface), std::move(geometryInterface), "odom"),
22 | lastTime_(std::numeric_limits::lowest()),
23 | minPublishTimeDifference_(1.0 / maxUpdateFrequency) {}
24 | void update(const SystemObservation& observation) {
25 | if (observation.time - lastTime_ > minPublishTimeDifference_) {
26 | lastTime_ = observation.time;
27 |
28 | publishDistances(mappingPtr_->getPinocchioJointPosition(observation.state));
29 | }
30 | }
31 |
32 | private:
33 | std::unique_ptr mappingPtr_;
34 |
35 | scalar_t lastTime_;
36 | scalar_t minPublishTimeDifference_;
37 | };
38 |
39 | } // namespace humanoid
40 | } // namespace ocs2
41 |
--------------------------------------------------------------------------------
/humanoid_controllers/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | humanoid_controllers
4 | 0.0.0
5 | The humanoid_controllers packages.
6 | Qiayuan Liao
7 | BSD
8 | Qiayuan Liao
9 |
10 |
11 | ament_cmake
12 | cmake_clang_tools
13 |
14 |
15 | rclcpp
16 | humanoid_interface
17 | humanoid_estimation
18 | humanoid_wbc
19 | geometry_msgs
20 | ocs2_msgs
21 | ocs2_ros_interfaces
22 | std_msgs
23 | humanoid_dummy
24 | ocs2_self_collision
25 | ocs2_self_collision_visualization
26 |
27 | angles
28 | hpp-fcl
29 | ament_lint_auto
30 | ament_lint_common
31 | controller_manager
32 |
33 | ament_cmake
34 |
35 |
36 |
37 |
--------------------------------------------------------------------------------
/humanoid_controllers/src/CheatControllerNode.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by pocket on 24-2-11.
3 | //
4 |
5 | #include "humanoid_controllers/humanoidController.h"
6 | #include
7 |
8 | using Duration = std::chrono::duration;
9 | using Clock = std::chrono::high_resolution_clock;
10 |
11 | bool pause_flag = false;
12 |
13 | void pauseCallback(const std_msgs::msg::Bool::SharedPtr msg){
14 | pause_flag = msg->data;
15 | std::cerr << "pause_flag: " << pause_flag << std::endl;
16 | }
17 |
18 | int main(int argc, char** argv){
19 | rclcpp::Duration elapsedTime_ = rclcpp::Duration::from_seconds(0.002);
20 |
21 |
22 | // Initialize ros node
23 | rclcpp::init(argc, argv);
24 | rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
25 | "humanoid_controller_node",
26 | rclcpp::NodeOptions()
27 | .allow_undeclared_parameters(true)
28 | .automatically_declare_parameters_from_overrides(true));
29 |
30 | //create a subscriber to pauseFlag
31 | auto pause_sub = node->create_subscription("pauseFlag", 1, pauseCallback);
32 | humanoid_controller::humanoidCheaterController controller;
33 | if (!controller.init(node)) {
34 | RCLCPP_ERROR(node->get_logger(),"Failed to initialize the humanoid controller!");
35 | return -1;
36 | }
37 |
38 | auto startTime = Clock::now();
39 | auto startTimeROS = node->get_clock()->now();
40 | controller.starting(startTimeROS);
41 | auto lastTime = startTime;
42 |
43 | //create a thread to spin the node
44 | std::thread spin_thread([node](){
45 | rclcpp::spin(node);
46 | });
47 | spin_thread.detach();
48 |
49 | while(rclcpp::ok()){
50 | if (!pause_flag)
51 | {
52 | const auto currentTime = Clock::now();
53 | // Compute desired duration rounded to clock decimation
54 | const Duration desiredDuration(1.0 / 500);
55 |
56 | // Get change in time
57 | Duration time_span = std::chrono::duration_cast(currentTime - lastTime);
58 | elapsedTime_ = rclcpp::Duration::from_seconds(time_span.count());
59 | lastTime = currentTime;
60 |
61 | // Check cycle time for excess delay
62 | // const double cycle_time_error = (elapsedTime_ - ros::Duration(desiredDuration.count())).toSec();
63 | // if (cycle_time_error > cycleTimeErrorThreshold_) {
64 | // ROS_WARN_STREAM("Cycle time exceeded error threshold by: " << cycle_time_error - cycleTimeErrorThreshold_ << "s, "
65 | // << "cycle time: " << elapsedTime_ << "s, "
66 | // << "threshold: " << cycleTimeErrorThreshold_ << "s");
67 | // }
68 |
69 | // Control
70 | // let the controller compute the new command (via the controller manager)
71 | controller.update(node->get_clock()->now(), elapsedTime_);
72 |
73 | // Sleep
74 | const auto sleepTill = currentTime + std::chrono::duration_cast(desiredDuration);
75 | std::this_thread::sleep_until(sleepTill);
76 | }
77 | }
78 |
79 |
80 |
81 | return 0;
82 | }
--------------------------------------------------------------------------------
/humanoid_controllers/src/NormalControllerNode.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by pocket on 24-2-11.
3 | //
4 |
5 | #include "humanoid_controllers/humanoidController.h"
6 | #include
7 | #include "rclcpp/rclcpp.hpp"
8 |
9 | using Duration = std::chrono::duration;
10 | using Clock = std::chrono::high_resolution_clock;
11 |
12 | bool pause_flag = false;
13 |
14 | void pauseCallback(const std_msgs::msg::Bool::SharedPtr msg){
15 | pause_flag = msg->data;
16 | std::cerr << "pause_flag: " << pause_flag << std::endl;
17 | }
18 |
19 | int main(int argc, char** argv){
20 | rclcpp::Duration elapsedTime_ = rclcpp::Duration::from_seconds(0.002);
21 |
22 | rclcpp::init(argc, argv);
23 | rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
24 | "humanoid_controller_node",
25 | rclcpp::NodeOptions()
26 | .allow_undeclared_parameters(true)
27 | .automatically_declare_parameters_from_overrides(true));
28 |
29 |
30 |
31 | //create a subscriber to pauseFlag
32 | auto pause_sub = node->create_subscription("pauseFlag", 1, pauseCallback);
33 | humanoid_controller::humanoidController controller;
34 |
35 | if (!controller.init(node)) {
36 | RCLCPP_ERROR(node->get_logger(),"Failed to initialize the humanoid controller!");
37 | return -1;
38 | }
39 |
40 | auto startTime = Clock::now();
41 | auto startTimeROS = node->get_clock()->now();
42 | controller.starting(startTimeROS);
43 | auto lastTime = startTime;
44 |
45 | //create a thread to spin the node
46 | std::thread spin_thread([node](){
47 | rclcpp::spin(node);
48 | });
49 | spin_thread.detach();
50 |
51 | while(rclcpp::ok()){
52 | if (!pause_flag)
53 | {
54 | const auto currentTime = Clock::now();
55 | // Compute desired duration rounded to clock decimation
56 | const Duration desiredDuration(1.0 / 500);
57 |
58 | // Get change in time
59 | Duration time_span = std::chrono::duration_cast(currentTime - lastTime);
60 | elapsedTime_ = rclcpp::Duration::from_seconds(time_span.count());
61 | lastTime = currentTime;
62 |
63 | // Check cycle time for excess delay
64 | // const double cycle_time_error = (elapsedTime_ - ros::Duration(desiredDuration.count())).toSec();
65 | // if (cycle_time_error > cycleTimeErrorThreshold_) {
66 | // ROS_WARN_STREAM("Cycle time exceeded error threshold by: " << cycle_time_error - cycleTimeErrorThreshold_ << "s, "
67 | // << "cycle time: " << elapsedTime_ << "s, "
68 | // << "threshold: " << cycleTimeErrorThreshold_ << "s");
69 | // }
70 |
71 | // Control
72 | // let the controller compute the new command (via the controller manager)
73 | controller.update(node->get_clock()->now(), elapsedTime_);
74 |
75 | // Sleep
76 | const auto sleepTill = currentTime + std::chrono::duration_cast(desiredDuration);
77 | std::this_thread::sleep_until(sleepTill);
78 | }
79 | }
80 |
81 |
82 |
83 | return 0;
84 | }
--------------------------------------------------------------------------------
/humanoid_dummy/include/humanoid_dummy/gait/GaitKeyboardPublisher.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 |
35 |
36 | #include
37 |
38 | #include
39 | #include
40 | #include
41 | #include
42 |
43 | namespace ocs2 {
44 | namespace humanoid {
45 |
46 | /** This class implements ModeSequence communication using ROS. */
47 | class GaitKeyboardPublisher {
48 | public:
49 | GaitKeyboardPublisher(const rclcpp::Node::SharedPtr &node, const std::string& gaitFile, const std::string& robotName, bool verbose = false);
50 |
51 | /** Prints the command line interface and responds to user input. Function returns after one user input. */
52 | void getKeyboardCommand();
53 | void publishGaitCommandFromString(const std::string& gaitCommand);
54 |
55 | private:
56 | /** Prints the list of available gaits. */
57 | void printGaitList(const std::vector& gaitList) const;
58 |
59 | std::vector gaitList_;
60 | std::map gaitMap_;
61 |
62 | rclcpp::Publisher::SharedPtr modeSequenceTemplatePublisher_;
63 | rclcpp::Publisher::SharedPtr modeSequencePublisher_;//发送的是string
64 | };
65 |
66 | } // namespace humanoid
67 | } // end of namespace ocs2
68 |
--------------------------------------------------------------------------------
/humanoid_dummy/include/humanoid_dummy/gait/GaitReceiver.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 |
34 | #include
35 |
36 | #include
37 | #include
38 | #include
39 |
40 | #include
41 | #include
42 | #include
43 |
44 | namespace ocs2 {
45 | namespace humanoid {
46 |
47 | class GaitReceiver : public SolverSynchronizedModule {
48 | public:
49 | GaitReceiver(const rclcpp::Node::SharedPtr &node, std::shared_ptr gaitSchedulePtr, const std::string& robotName);
50 |
51 | void preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& currentState,
52 | const ReferenceManagerInterface& referenceManager) override;
53 |
54 | void postSolverRun(const PrimalSolution& primalSolution) override{};
55 |
56 | private:
57 | void mpcModeSequenceCallback(const ocs2_msgs::msg::ModeSchedule::ConstSharedPtr& msg);
58 |
59 | std::shared_ptr gaitSchedulePtr_;
60 |
61 | rclcpp::Subscription::SharedPtr mpcModeSequenceSubscriber_;
62 |
63 | std::mutex receivedGaitMutex_;
64 | std::atomic_bool gaitUpdated_;
65 | ModeSequenceTemplate receivedGait_;
66 | };
67 |
68 | } // namespace humanoid
69 | } // namespace ocs2
70 |
--------------------------------------------------------------------------------
/humanoid_dummy/include/humanoid_dummy/gait/ModeSequenceTemplateRos.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 |
34 | #include
35 |
36 | #include
37 |
38 | namespace ocs2 {
39 | namespace humanoid {
40 |
41 | /** Convert mode sequence template to ROS message */
42 | inline ocs2_msgs::msg::ModeSchedule createModeSequenceTemplateMsg(const ModeSequenceTemplate& modeSequenceTemplate) {
43 | ::ocs2_msgs::msg::ModeSchedule modeScheduleMsg;
44 | modeScheduleMsg.event_times.assign(modeSequenceTemplate.switchingTimes.begin(), modeSequenceTemplate.switchingTimes.end());
45 | modeScheduleMsg.mode_sequence.assign(modeSequenceTemplate.modeSequence.begin(), modeSequenceTemplate.modeSequence.end());
46 | return modeScheduleMsg;
47 | }
48 |
49 | /** Convert ROS message to mode sequence template */
50 | inline ModeSequenceTemplate readModeSequenceTemplateMsg(const ocs2_msgs::msg::ModeSchedule& modeScheduleMsg) {
51 | std::vector switchingTimes(modeScheduleMsg.event_times.begin(), modeScheduleMsg.event_times.end());
52 | std::vector modeSequence(modeScheduleMsg.mode_sequence.begin(), modeScheduleMsg.mode_sequence.end());
53 | return {switchingTimes, modeSequence};
54 | }
55 |
56 | } // namespace humanoid
57 | } // namespace ocs2
58 |
--------------------------------------------------------------------------------
/humanoid_dummy/launch/multiplot.launch.py:
--------------------------------------------------------------------------------
1 | import os
2 | import sys
3 |
4 | import launch
5 | import launch_ros.actions
6 | from ament_index_python.packages import get_package_share_directory
7 |
8 |
9 | def generate_launch_description():
10 | ld = launch.LaunchDescription([
11 | launch.actions.DeclareLaunchArgument(
12 | name='metrics_config',
13 | default_value=get_package_share_directory(
14 | 'humanoid_interface') + '/config/multiplot/zero_velocity.xml'
15 | ),
16 | launch_ros.actions.Node(
17 | package='rqt_multiplot',
18 | executable='rqt_multiplot',
19 | name='mpc_metrics',
20 | output='screen'
21 | ),
22 | launch.actions.IncludeLaunchDescription(
23 | launch.launch_description_sources.PythonLaunchDescriptionSource(
24 | os.path.join(get_package_share_directory(
25 | 'ocs2_ros_interfaces'), 'launch/performance_indices.launch.py')
26 | ),
27 | launch_arguments={
28 | 'mpc_policy_topic_name': 'humanoid_mpc_policy'
29 | }.items()
30 | )
31 | ])
32 | return ld
33 |
34 |
35 | if __name__ == '__main__':
36 | generate_launch_description()
37 |
--------------------------------------------------------------------------------
/humanoid_dummy/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | humanoid_dummy
4 | 0.0.1
5 | The humanoid_dummy package
6 |
7 | Farbod Farshidian
8 | Ruben Grandia
9 | Jean-Pierre Sleiman
10 |
11 | BSD-3
12 |
13 | ament_cmake
14 |
15 | rclcpp
16 | tf2_ros
17 | urdf
18 | kdl_parser
19 | robot_state_publisher
20 |
21 |
22 | hpp-fcl
23 | ocs2_core
24 | ocs2_oc
25 | ocs2_ddp
26 | ocs2_mpc
27 | ocs2_sqp
28 | ocs2_ipm
29 | ocs2_robotic_tools
30 | ocs2_pinocchio_interface
31 | ocs2_centroidal_model
32 | ocs2_robotic_assets
33 | ocs2_msgs
34 | humanoid_interface
35 | ocs2_ros_interfaces
36 |
37 | pinocchio
38 |
39 |
40 | ament_cmake_gtest
41 | ament_lint_auto
42 | ament_lint_common
43 |
44 |
45 | ament_cmake
46 |
47 |
48 |
49 |
--------------------------------------------------------------------------------
/humanoid_dummy/src/HumanoidDummyNode.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include "rclcpp/rclcpp.hpp"
31 |
32 | #include
33 | #include
34 | #include
35 | #include
36 | #include
37 |
38 | #include "humanoid_dummy/visualization/HumanoidVisualizer.h"
39 |
40 | using namespace ocs2;
41 | using namespace humanoid;
42 |
43 | int main(int argc, char** argv) {
44 | const std::string robotName = "humanoid";
45 |
46 | // Initialize ros node
47 | rclcpp::init(argc, argv);
48 | rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
49 | robotName + "_mrt",
50 | rclcpp::NodeOptions()
51 | .allow_undeclared_parameters(true)
52 | .automatically_declare_parameters_from_overrides(true));
53 | // Get node parameters
54 | const std::string taskFile = node->get_parameter("taskFile").as_string();
55 | const std::string urdfFile = node->get_parameter("urdfFile").as_string();
56 | const std::string referenceFile = node->get_parameter("referenceFile").as_string();
57 |
58 | // Robot interface
59 | HumanoidInterface interface(taskFile, urdfFile, referenceFile);
60 |
61 | // MRT
62 | MRT_ROS_Interface mrt(robotName);
63 | mrt.initRollout(&interface.getRollout());
64 | mrt.launchNodes(node);
65 |
66 | // Visualization
67 | CentroidalModelPinocchioMapping pinocchioMapping(interface.getCentroidalModelInfo());
68 | PinocchioEndEffectorKinematics endEffectorKinematics(interface.getPinocchioInterface(), pinocchioMapping,
69 | interface.modelSettings().contactNames3DoF);
70 | auto humanoidVisualizer = std::make_shared(
71 | interface.getPinocchioInterface(), interface.getCentroidalModelInfo(), endEffectorKinematics, node);
72 |
73 | // Dummy legged robot
74 | MRT_ROS_Dummy_Loop HumanoidDummySimulator(mrt, interface.mpcSettings().mrtDesiredFrequency_,
75 | interface.mpcSettings().mpcDesiredFrequency_);
76 | HumanoidDummySimulator.subscribeObservers({humanoidVisualizer});
77 |
78 | // Initial state
79 | SystemObservation initObservation;
80 | initObservation.state = interface.getInitialState();
81 | initObservation.input = vector_t::Zero(interface.getCentroidalModelInfo().inputDim);
82 | initObservation.mode = ModeNumber::STANCE;
83 |
84 | // Initial command
85 | TargetTrajectories initTargetTrajectories({0.0}, {initObservation.state}, {initObservation.input});
86 |
87 | // run dummy
88 | HumanoidDummySimulator.run(initObservation, initTargetTrajectories);
89 |
90 | // Successful exit
91 | return 0;
92 | }
93 |
--------------------------------------------------------------------------------
/humanoid_dummy/src/HumanoidGaitCommandNode.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include "rclcpp/rclcpp.hpp"
31 |
32 | #include "humanoid_dummy/gait/GaitKeyboardPublisher.h"
33 |
34 | using namespace ocs2;
35 | using namespace humanoid;
36 |
37 | int main(int argc, char* argv[]) {
38 | const std::string robotName = "humanoid";
39 |
40 | // Initialize ros node
41 | rclcpp::init(argc, argv);
42 | rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
43 | robotName + "_mpc_mode_schedule",
44 | rclcpp::NodeOptions()
45 | .allow_undeclared_parameters(true)
46 | .automatically_declare_parameters_from_overrides(true));
47 | // Get node parameters
48 | const std::string gaitCommandFile = node->get_parameter("gaitCommandFile").as_string();
49 | std::cerr << "Loading gait file: " << gaitCommandFile << std::endl;
50 |
51 | GaitKeyboardPublisher gaitCommand(node, gaitCommandFile, robotName, true);
52 |
53 | while (rclcpp::ok()) {
54 | gaitCommand.getKeyboardCommand();
55 | }
56 |
57 | // Successful exit
58 | return 0;
59 | }
60 |
--------------------------------------------------------------------------------
/humanoid_dummy/src/HumanoidSqpMpcNode.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2017, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include "rclcpp/rclcpp.hpp"
31 | #include
32 | #include
33 | #include
34 | #include
35 | #include
36 |
37 | #include "humanoid_dummy/gait/GaitReceiver.h"
38 |
39 | using namespace ocs2;
40 | using namespace humanoid;
41 |
42 | int main(int argc, char** argv) {
43 | const std::string robotName = "humanoid";
44 |
45 | // Initialize ros node
46 | rclcpp::init(argc, argv);
47 | rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
48 | robotName + "_mpc",
49 | rclcpp::NodeOptions()
50 | .allow_undeclared_parameters(true)
51 | .automatically_declare_parameters_from_overrides(true));
52 | // Get node parameters
53 | bool multiplot = false;
54 |
55 | multiplot = node->get_parameter("multiplot").as_bool();
56 | const std::string taskFile = node->get_parameter("taskFile").as_string();
57 | const std::string urdfFile = node->get_parameter("urdfFile").as_string();
58 | const std::string referenceFile = node->get_parameter("referenceFile").as_string();
59 |
60 | // Robot interface
61 | HumanoidInterface interface(taskFile, urdfFile, referenceFile);
62 |
63 | // Gait receiver
64 | auto gaitReceiverPtr =
65 | std::make_shared(node, interface.getSwitchedModelReferenceManagerPtr()->getGaitSchedule(), robotName);
66 |
67 | // ROS ReferenceManager
68 | auto rosReferenceManagerPtr = std::make_shared(robotName, interface.getReferenceManagerPtr());
69 | rosReferenceManagerPtr->subscribe(node);
70 |
71 | // MPC
72 | SqpMpc mpc(interface.mpcSettings(), interface.sqpSettings(), interface.getOptimalControlProblem(), interface.getInitializer());
73 | mpc.getSolverPtr()->setReferenceManager(rosReferenceManagerPtr);
74 | mpc.getSolverPtr()->addSynchronizedModule(gaitReceiverPtr);
75 |
76 | // observer for zero velocity constraints (only add this for debugging as it slows down the solver)
77 | if (multiplot) {
78 | auto createStateInputBoundsObserver = [&](const std::string& termName) {
79 | const ocs2::scalar_array_t observingTimePoints{0.0};
80 | const std::vector topicNames{"metrics/" + termName + "/0MsLookAhead"};
81 | auto callback = ocs2::ros::createConstraintCallback(node, {0.0}, topicNames,
82 | ocs2::ros::CallbackInterpolationStrategy::linear_interpolation);
83 | return ocs2::SolverObserver::ConstraintTermObserver(ocs2::SolverObserver::Type::Intermediate, termName, std::move(callback));
84 | };
85 | for (size_t i = 0; i < interface.getCentroidalModelInfo().numSixDofContacts; i++) {
86 | const std::string& footName = interface.modelSettings().contactNames3DoF[i];
87 | mpc.getSolverPtr()->addSolverObserver(createStateInputBoundsObserver(footName + "_zeroVelocity"));
88 | }
89 | }
90 |
91 | // Launch MPC ROS node
92 | MPC_ROS_Interface mpcNode(mpc, robotName);
93 | mpcNode.launchNodes(node);
94 |
95 | // Successful exit
96 | return 0;
97 | }
98 |
--------------------------------------------------------------------------------
/humanoid_dummy/src/gait/GaitReceiver.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include "humanoid_dummy/gait/GaitReceiver.h"
31 |
32 | #include "humanoid_dummy/gait/ModeSequenceTemplateRos.h"
33 |
34 | namespace ocs2 {
35 | namespace humanoid {
36 |
37 | /******************************************************************************************************/
38 | /******************************************************************************************************/
39 | /******************************************************************************************************/
40 | GaitReceiver::GaitReceiver(const rclcpp::Node::SharedPtr &node, std::shared_ptr gaitSchedulePtr, const std::string& robotName)
41 | : gaitSchedulePtr_(std::move(gaitSchedulePtr)), receivedGait_({0.0, 1.0}, {ModeNumber::STANCE}), gaitUpdated_(false) {
42 | mpcModeSequenceSubscriber_ = node->create_subscription(robotName + "_mpc_mode_schedule", 1, std::bind(&GaitReceiver::mpcModeSequenceCallback, this,
43 | std::placeholders::_1));
44 | }
45 |
46 | /******************************************************************************************************/
47 | /******************************************************************************************************/
48 | /******************************************************************************************************/
49 | void GaitReceiver::preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& currentState,
50 | const ReferenceManagerInterface& referenceManager) {
51 | if (gaitUpdated_) {
52 | std::lock_guard lock(receivedGaitMutex_);
53 | std::cerr << "[GaitReceiver]: Setting new gait after time " << finalTime << "\n";
54 | std::cerr << receivedGait_;
55 | const auto timeHorizon = finalTime - initTime;
56 | gaitSchedulePtr_->insertModeSequenceTemplate(receivedGait_, finalTime, timeHorizon);
57 | gaitUpdated_ = false;
58 | }
59 | }
60 |
61 | /******************************************************************************************************/
62 | /******************************************************************************************************/
63 | /******************************************************************************************************/
64 | void GaitReceiver::mpcModeSequenceCallback(const ocs2_msgs::msg::ModeSchedule::ConstSharedPtr& msg) {
65 | std::lock_guard lock(receivedGaitMutex_);
66 | receivedGait_ = readModeSequenceTemplateMsg(*msg);
67 | gaitUpdated_ = true;
68 | }
69 |
70 | } // namespace humanoid
71 | } // namespace ocs2
72 |
--------------------------------------------------------------------------------
/humanoid_estimation/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.14)
2 | set(CMAKE_CXX_STANDARD 17)
3 | project(humanoid_estimation)
4 |
5 | set(CMAKE_BUILD_TYPE Release)
6 | set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
7 |
8 | set(dependencies
9 | rclcpp
10 | hardware_interface
11 | tf2_ros
12 | nav_msgs
13 | humanoid_interface
14 | geometry_msgs
15 | tf2_geometry_msgs
16 | )
17 |
18 | find_package(ament_cmake REQUIRED)
19 | find_package(geometry_msgs REQUIRED)
20 | find_package(tf2_ros REQUIRED)
21 | find_package(nav_msgs REQUIRED)
22 | find_package(humanoid_interface REQUIRED)
23 | find_package(PkgConfig REQUIRED)
24 | find_package(hardware_interface REQUIRED)
25 | find_package(tf2_geometry_msgs REQUIRED)
26 | pkg_check_modules(pinocchio REQUIRED pinocchio)
27 |
28 | ###########
29 | ## Build ##
30 | ###########
31 |
32 | # Resolve for the package path at compile time.
33 |
34 |
35 | set(FLAGS
36 | ${OCS2_CXX_FLAGS}
37 | ${pinocchio_CFLAGS_OTHER}
38 | -Wno-ignored-attributes
39 | -Wno-invalid-partial-specialization # to silence warning with unsupported Eigen Tensor
40 | -DPINOCCHIO_URDFDOM_TYPEDEF_SHARED_PTR
41 | -DPINOCCHIO_URDFDOM_USE_STD_SHARED_PTR
42 | )
43 |
44 | # Legged robot interface library
45 | add_library(${PROJECT_NAME}
46 | src/StateEstimateBase.cpp
47 | src/FromTopicEstimate.cpp
48 | src/LinearKalmanFilter.cpp
49 | )
50 |
51 | target_include_directories(${PROJECT_NAME}
52 | PUBLIC
53 | "$"
54 | "$")
55 |
56 | ament_target_dependencies(${PROJECT_NAME} ${dependencies})
57 | target_compile_options(${PROJECT_NAME} PUBLIC ${FLAGS})
58 |
59 | #########################
60 | ### CLANG TOOLING ###
61 | #########################
62 |
63 | find_package(cmake_clang_tools QUIET)
64 | if (cmake_clang_tools_FOUND)
65 | message(STATUS "Run clang tooling for target ocs2_legged_robot")
66 | add_clang_tooling(
67 | TARGETS ${PROJECT_NAME}
68 | SOURCE_DIRS src include test
69 | CT_HEADER_DIRS include
70 | CF_WERROR
71 | )
72 | endif (cmake_clang_tools_FOUND)
73 |
74 | #############
75 | ## Install ##
76 | #############
77 |
78 | install(
79 | DIRECTORY include/
80 | DESTINATION include/${PROJECT_NAME}
81 | )
82 |
83 | install(
84 | TARGETS ${PROJECT_NAME}
85 | EXPORT export_${PROJECT_NAME}
86 | ARCHIVE DESTINATION lib
87 | LIBRARY DESTINATION lib
88 | RUNTIME DESTINATION bin
89 | )
90 |
91 | install(
92 | DIRECTORY
93 | DESTINATION share/${PROJECT_NAME}/
94 | )
95 |
96 | ament_export_dependencies(${dependencies})
97 | ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
98 |
99 | #############
100 | ## Testing ##
101 | #############
102 |
103 |
104 | ament_package()
105 |
106 |
--------------------------------------------------------------------------------
/humanoid_estimation/include/humanoid_estimation/FromTopiceEstimate.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by qiayuan on 2022/7/24.
3 | //
4 |
5 | /********************************************************************************
6 | Modified Copyright (c) 2023-2024, BridgeDP Robotics.Co.Ltd. All rights reserved.
7 |
8 | For further information, contact: contact@bridgedp.com or visit our website
9 | at www.bridgedp.com.
10 | ********************************************************************************/
11 |
12 | #include "humanoid_estimation/StateEstimateBase.h"
13 |
14 |
15 |
16 | #pragma once
17 | namespace ocs2
18 | {
19 | namespace humanoid
20 | {
21 |
22 | class FromTopicStateEstimate : public StateEstimateBase
23 | {
24 | public:
25 | FromTopicStateEstimate(PinocchioInterface pinocchioInterface, CentroidalModelInfo info,
26 | const PinocchioEndEffectorKinematics& eeKinematics, const rclcpp::Node::SharedPtr &node);
27 |
28 | void updateImu(const Eigen::Quaternion& quat, const vector3_t& angularVelLocal,
29 | const vector3_t& linearAccelLocal, const matrix3_t& orientationCovariance,
30 | const matrix3_t& angularVelCovariance, const matrix3_t& linearAccelCovariance) override{};
31 |
32 | vector_t update(const rclcpp::Time& time, const rclcpp::Duration& period) override;
33 |
34 | private:
35 | void callback(const nav_msgs::msg::Odometry::SharedPtr msg);
36 |
37 |
38 | rclcpp::Subscription::SharedPtr sub_;
39 | nav_msgs::msg::Odometry buffer_;
40 | };
41 |
42 | } // namespace humanoid
43 | } // namespace ocs2
44 |
--------------------------------------------------------------------------------
/humanoid_estimation/include/humanoid_estimation/LinearKalmanFilter.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by qiayuan on 2022/7/24.
3 | //
4 |
5 | /********************************************************************************
6 | Modified Copyright (c) 2023-2024, BridgeDP Robotics.Co.Ltd. All rights reserved.
7 |
8 | For further information, contact: contact@bridgedp.com or visit our website
9 | at www.bridgedp.com.
10 | ********************************************************************************/
11 |
12 | #pragma once
13 |
14 | #include "humanoid_estimation/StateEstimateBase.h"
15 |
16 | #include
17 | #include
18 |
19 |
20 |
21 | #include
22 | #include
23 | #include
24 | #include
25 |
26 | namespace ocs2
27 | {
28 | namespace humanoid
29 | {
30 |
31 | class KalmanFilterEstimate : public StateEstimateBase
32 | {
33 | public:
34 | KalmanFilterEstimate(PinocchioInterface pinocchioInterface, CentroidalModelInfo info,
35 | const PinocchioEndEffectorKinematics& eeKinematics , const rclcpp::Node::SharedPtr &node);
36 |
37 | vector_t update(const rclcpp::Time& time, const rclcpp::Duration& period) override;
38 |
39 | void loadSettings(const std::string& taskFile, bool verbose);
40 |
41 |
42 |
43 |
44 |
45 | protected:
46 | void updateFromTopic();
47 |
48 | void callback(const nav_msgs::msg::Odometry::SharedPtr msg);
49 |
50 | nav_msgs::msg::Odometry getOdomMsg();
51 |
52 | vector_t feetHeights_;
53 |
54 | // Config
55 | scalar_t footRadius_ = 0.02;
56 | scalar_t imuProcessNoisePosition_ = 0.02;
57 | scalar_t imuProcessNoiseVelocity_ = 0.02;
58 | scalar_t footProcessNoisePosition_ = 0.002;
59 | scalar_t footSensorNoisePosition_ = 0.005;
60 | scalar_t footSensorNoiseVelocity_ = 0.1;
61 | scalar_t footHeightSensorNoise_ = 0.01;
62 |
63 | private:
64 | Eigen::Matrix xHat_;
65 | Eigen::Matrix ps_;
66 | Eigen::Matrix vs_;
67 | Eigen::Matrix a_;
68 | Eigen::Matrix q_;
69 | Eigen::Matrix p_;
70 | Eigen::Matrix r_;
71 | Eigen::Matrix b_;
72 | Eigen::Matrix c_;
73 |
74 | // Topic
75 |
76 | rclcpp::Subscription::SharedPtr sub_;
77 | nav_msgs::msg::Odometry buffer_;
78 | tf2_ros::Buffer tfBuffer_;
79 | tf2_ros::TransformListener tfListener_;
80 | tf2::Transform world2odom_;
81 | std::string frameOdom_, frameGuess_;
82 | bool topicUpdated_ = false;
83 | };
84 |
85 | } // namespace humanoid
86 | } // namespace ocs2
87 |
--------------------------------------------------------------------------------
/humanoid_estimation/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | humanoid_estimation
4 | 0.0.0
5 | The humanoid_estimation packages.
6 | bridgedp
7 | MIT
8 |
9 | ament_cmake
10 |
11 | cmake_clang_tools
12 | nav_msgs
13 | tf2_ros
14 | tf2_geometry_msgs
15 | rclcpp
16 | geometry_msgs
17 | humanoid_interface
18 | hardware_interface
19 |
20 |
21 |
22 | ament_cmake
23 |
24 |
25 |
26 |
27 |
--------------------------------------------------------------------------------
/humanoid_estimation/src/FromTopicEstimate.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by qiayuan on 2022/7/24.
3 | //
4 |
5 | /********************************************************************************
6 | Modified Copyright (c) 2023-2024, BridgeDP Robotics.Co.Ltd. All rights reserved.
7 |
8 | For further information, contact: contact@bridgedp.com or visit our website
9 | at www.bridgedp.com.
10 | ********************************************************************************/
11 |
12 | #include "humanoid_estimation/FromTopiceEstimate.h"
13 | #include
14 |
15 |
16 | namespace ocs2
17 | {
18 | namespace humanoid
19 | {
20 | FromTopicStateEstimate::FromTopicStateEstimate(PinocchioInterface pinocchioInterface, CentroidalModelInfo info,
21 | const PinocchioEndEffectorKinematics& eeKinematics, const rclcpp::Node::SharedPtr &node)
22 | : StateEstimateBase(std::move(pinocchioInterface), std::move(info), eeKinematics , node)
23 | {
24 | sub_ = node->create_subscription("/ground_truth/state", 10, std::bind(&FromTopicStateEstimate::callback, this, std::placeholders::_1));
25 | }
26 |
27 | void FromTopicStateEstimate::callback(const nav_msgs::msg::Odometry::SharedPtr msg)
28 | {
29 | buffer_ = *msg;
30 | }
31 |
32 | vector_t FromTopicStateEstimate::update(const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/)
33 | {
34 | nav_msgs::msg::Odometry odom = buffer_;
35 |
36 | Eigen::Quaternion quat(odom.pose.pose.orientation.w, odom.pose.pose.orientation.x, odom.pose.pose.orientation.y,
37 | odom.pose.pose.orientation.z);
38 | auto angularVelLocal = Eigen::Matrix(odom.twist.twist.angular.x, odom.twist.twist.angular.y,
39 | odom.twist.twist.angular.z);
40 | auto linearVelLocal = Eigen::Matrix(odom.twist.twist.linear.x, odom.twist.twist.linear.y,
41 | odom.twist.twist.linear.z);
42 |
43 | Eigen::Matrix linearVelWorld = quat.matrix() * linearVelLocal;
44 |
45 | vector3_t zyx = quatToZyx(quat) - zyxOffset_;
46 | vector3_t angularVelGlobal = getGlobalAngularVelocityFromEulerAnglesZyxDerivatives(
47 | zyx, getEulerAnglesZyxDerivativesFromLocalAngularVelocity(quatToZyx(quat), angularVelLocal));
48 | updateAngular(zyx, angularVelGlobal);
49 |
50 | // updateAngular(quatToZyx(Eigen::Quaternion(odom.pose.pose.orientation.w, odom.pose.pose.orientation.x,
51 | // odom.pose.pose.orientation.y, odom.pose.pose.orientation.z)),
52 | // Eigen::Matrix(odom.twist.twist.angular.x, odom.twist.twist.angular.y,
53 | // odom.twist.twist.angular.z));
54 | updateLinear(
55 | Eigen::Matrix(odom.pose.pose.position.x, odom.pose.pose.position.y, odom.pose.pose.position.z),
56 | Eigen::Matrix(odom.twist.twist.linear.x, odom.twist.twist.linear.y, odom.twist.twist.linear.z));
57 | //linearVelWorld);
58 |
59 | publishMsgs(odom);
60 |
61 | return rbdState_;
62 | }
63 |
64 | } // namespace humanoid
65 | } // namespace ocs2
--------------------------------------------------------------------------------
/humanoid_interface/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.14)
2 | set(CMAKE_CXX_STANDARD 17)
3 | project(humanoid_interface)
4 |
5 | set(CMAKE_BUILD_TYPE Release)
6 | set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
7 |
8 | set(dependencies
9 | ocs2_core
10 | ocs2_oc
11 | ocs2_ddp
12 | ocs2_mpc
13 | ocs2_sqp
14 | ocs2_ipm
15 | ocs2_robotic_tools
16 | ocs2_pinocchio_interface
17 | ocs2_centroidal_model
18 | ocs2_robotic_assets
19 | ocs2_self_collision
20 | )
21 |
22 | find_package(ament_cmake REQUIRED)
23 | find_package(ocs2_core REQUIRED)
24 | find_package(ocs2_oc REQUIRED)
25 | find_package(ocs2_ddp REQUIRED)
26 | find_package(ocs2_mpc REQUIRED)
27 | find_package(ocs2_sqp REQUIRED)
28 | find_package(ocs2_ipm REQUIRED)
29 | find_package(ocs2_centroidal_model REQUIRED)
30 | find_package(ocs2_pinocchio_interface REQUIRED)
31 | find_package(ocs2_robotic_assets REQUIRED)
32 | find_package(ocs2_robotic_tools REQUIRED)
33 | find_package(ocs2_self_collision REQUIRED)
34 |
35 | ###########
36 | ## Build ##
37 | ###########
38 |
39 | # Resolve for the package path at compile time.
40 | configure_file(
41 | "${PROJECT_SOURCE_DIR}/include/${PROJECT_NAME}/package_path.h.in"
42 | "${PROJECT_BINARY_DIR}/include/${PROJECT_NAME}/package_path.h" @ONLY
43 | )
44 |
45 | set(FLAGS
46 | ${OCS2_CXX_FLAGS}
47 | ${pinocchio_CFLAGS_OTHER}
48 | -Wno-ignored-attributes
49 | -Wno-invalid-partial-specialization # to silence warning with unsupported Eigen Tensor
50 | -DPINOCCHIO_URDFDOM_TYPEDEF_SHARED_PTR
51 | -DPINOCCHIO_URDFDOM_USE_STD_SHARED_PTR
52 | )
53 |
54 | # Legged robot interface library
55 | add_library(${PROJECT_NAME}
56 | src/common/ModelSettings.cpp
57 | src/dynamics/HumanoidDynamicsAD.cpp
58 | src/constraint/EndEffectorLinearConstraint.cpp
59 | src/constraint/FrictionConeConstraint.cpp
60 | src/constraint/ZeroForceConstraint.cpp
61 | src/constraint/NormalVelocityConstraintCppAd.cpp
62 | src/constraint/ZeroVelocityConstraintCppAd.cpp
63 | src/constraint/FootRollContraint.cpp
64 | src/initialization/HumanoidInitializer.cpp
65 | src/reference_manager/SwitchedModelReferenceManager.cpp
66 | src/foot_planner/CubicSpline.cpp
67 | src/foot_planner/SplineCpg.cpp
68 | src/foot_planner/SwingTrajectoryPlanner.cpp
69 | src/gait/Gait.cpp
70 | src/gait/GaitSchedule.cpp
71 | src/gait/LegLogic.cpp
72 | src/gait/ModeSequenceTemplate.cpp
73 | src/HumanoidInterface.cpp
74 | src/HumanoidPreComputation.cpp
75 | )
76 |
77 | target_include_directories(${PROJECT_NAME}
78 | PUBLIC
79 | "$"
80 | "$")
81 |
82 | ament_target_dependencies(${PROJECT_NAME} ${dependencies})
83 | target_compile_options(${PROJECT_NAME} PUBLIC ${FLAGS})
84 |
85 | #########################
86 | ### CLANG TOOLING ###
87 | #########################
88 |
89 | find_package(cmake_clang_tools QUIET)
90 | if (cmake_clang_tools_FOUND)
91 | message(STATUS "Run clang tooling for target ocs2_legged_robot")
92 | add_clang_tooling(
93 | TARGETS ${PROJECT_NAME}
94 | SOURCE_DIRS src include test
95 | CT_HEADER_DIRS include
96 | CF_WERROR
97 | )
98 | endif (cmake_clang_tools_FOUND)
99 |
100 | #############
101 | ## Install ##
102 | #############
103 |
104 | install(
105 | DIRECTORY include/
106 | DESTINATION include/${PROJECT_NAME}
107 | )
108 |
109 | install(
110 | TARGETS ${PROJECT_NAME}
111 | EXPORT export_${PROJECT_NAME}
112 | ARCHIVE DESTINATION lib
113 | LIBRARY DESTINATION lib
114 | RUNTIME DESTINATION bin
115 | )
116 |
117 | install(
118 | DIRECTORY config
119 | DESTINATION share/${PROJECT_NAME}/
120 | )
121 |
122 | ament_export_dependencies(${dependencies})
123 | ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
124 |
125 | #############
126 | ## Testing ##
127 | #############
128 | find_package(ament_lint_auto REQUIRED)
129 | ament_lint_auto_find_test_dependencies()
130 |
131 | if (BUILD_TESTING)
132 | find_package(ament_cmake_gtest)
133 |
134 | ament_add_gtest(${PROJECT_NAME}_test
135 | test/AnymalFactoryFunctions.cpp
136 | test/constraint/testEndEffectorLinearConstraint.cpp
137 | test/constraint/testFrictionConeConstraint.cpp
138 | test/constraint/testZeroForceConstraint.cpp
139 | )
140 | target_include_directories(${PROJECT_NAME}_test PRIVATE
141 | test/include
142 | ${PROJECT_BINARY_DIR}/include
143 | )
144 | ament_target_dependencies(${PROJECT_NAME}_test ${dependencies})
145 | target_link_libraries(${PROJECT_NAME}_test ${PROJECT_NAME})
146 | target_compile_options(${PROJECT_NAME}_test PRIVATE ${FLAGS})
147 | endif ()
148 |
149 | ament_package()
--------------------------------------------------------------------------------
/humanoid_interface/auto_generated/.gitignore:
--------------------------------------------------------------------------------
1 | # Ignore everything in this directory
2 | *
3 | # Except this file
4 | !.gitignore
5 |
6 |
--------------------------------------------------------------------------------
/humanoid_interface/config/command/gait.info:
--------------------------------------------------------------------------------
1 | list
2 | {
3 | [0] stance
4 | [1] trot
5 | [2] walk
6 | [3] quick_trot
7 | }
8 |
9 | stance
10 | {
11 | modeSequence
12 | {
13 | [0] STANCE
14 | }
15 | switchingTimes
16 | {
17 | [0] 0.0
18 | [1] 1000.0
19 | }
20 | }
21 |
22 | trot
23 | {
24 | modeSequence
25 | {
26 | [0] LCONTACT
27 | [1] RCONTACT
28 | }
29 | switchingTimes
30 | {
31 | [0] 0.0
32 | [1] 0.45
33 | [2] 0.9
34 | }
35 | }
36 |
37 | walk
38 | {
39 | modeSequence
40 | {
41 | [0] LCONTACT
42 | [1] STANCE
43 | [2] RCONTACT
44 | [3] STANCE
45 | }
46 | switchingTimes
47 | {
48 | [0] 0.0 ;
49 | [1] 0.4 ;0.45
50 | [2] 0.6 ;0.6
51 | [3] 1.0 ;1.05
52 | [4] 1.2 ;1.2
53 | }
54 | }
55 |
56 | quick_trot
57 | {
58 | modeSequence
59 | {
60 | [0] LCONTACT
61 | [1] RCONTACT
62 | }
63 | switchingTimes
64 | {
65 | [0] 0.0
66 | [1] 0.3
67 | [2] 0.6
68 | }
69 | }
70 |
--------------------------------------------------------------------------------
/humanoid_interface/config/command/gait_.info:
--------------------------------------------------------------------------------
1 | list
2 | {
3 | [0] stance
4 | [1] trot
5 | [2] walk
6 | [3] quick_trot
7 | }
8 |
9 | stance
10 | {
11 | modeSequence
12 | {
13 | [0] STANCE
14 | }
15 | switchingTimes
16 | {
17 | [0] 0.0
18 | [1] 1000.0
19 | }
20 | }
21 |
22 | trot
23 | {
24 | modeSequence
25 | {
26 | [0] LCONTACT
27 | [1] RCONTACT
28 | }
29 | switchingTimes
30 | {
31 | [0] 0.0
32 | [1] 0.45
33 | [2] 0.9
34 | }
35 | }
36 |
37 | walk
38 | {
39 | modeSequence
40 | {
41 | [0] LCONTACT
42 | [1] STANCE
43 | [2] RCONTACT
44 | [3] STANCE
45 | }
46 | switchingTimes
47 | {
48 | [0] 0.0
49 | [1] 0.45
50 | [2] 0.6
51 | [3] 1.05
52 | [4] 1.2
53 | }
54 | }
55 |
56 | quick_trot
57 | {
58 | modeSequence
59 | {
60 | [0] LCONTACT
61 | [1] RCONTACT
62 | }
63 | switchingTimes
64 | {
65 | [0] 0.0
66 | [1] 0.3
67 | [2] 0.6
68 | }
69 | }
70 |
--------------------------------------------------------------------------------
/humanoid_interface/config/command/reference.info:
--------------------------------------------------------------------------------
1 | targetDisplacementVelocity 0.5;
2 | targetRotationVelocity 0.3;
3 |
4 | comHeight 0.82831
5 |
6 | defaultJointState
7 | {
8 | (0,0) 0.04 ; leg_l1_joint
9 | (1,0) 0.0 ; leg_l2_joint
10 | (2,0) 0.27 ; leg_l3_joint
11 | (3,0) 0.71 ; leg_l4_joint
12 | (4,0) 0.44 ; leg_l5_joint
13 | (5,0) -0.04 ; leg_l6_joint
14 | (6,0) -0.04 ; leg_r1_joint -0.04
15 | (7,0) 0.0 ; leg_r2_joint
16 | (8,0) 0.27 ; leg_r3_joint
17 | (9,0) 0.71 ; leg_r4_joint
18 | (10,0) 0.44 ; leg_r5_joint
19 | (11,0) 0.04 ; leg_r6_joint
20 | }
21 |
22 | initialModeSchedule
23 | {
24 | modeSequence
25 | {
26 | [0] STANCE
27 | [1] STANCE
28 | }
29 | eventTimes
30 | {
31 | [0] 1000.0 ; not used
32 | }
33 | }
34 |
35 | defaultModeSequenceTemplate
36 | {
37 | modeSequence
38 | {
39 | [0] STANCE
40 | }
41 | switchingTimes
42 | {
43 | [0] 0.0
44 | [1] 1000.0
45 | }
46 | }
47 |
--------------------------------------------------------------------------------
/humanoid_interface/config/command/reference_.info:
--------------------------------------------------------------------------------
1 | targetDisplacementVelocity 0.7;
2 | targetRotationVelocity 0.5;
3 |
4 | comHeight 0.8195
5 |
6 | defaultJointState
7 | {
8 | (0,0) 0.05 ; leg_l1_joint
9 | (1,0) 0.0 ; leg_l2_joint
10 | (2,0) 0.37 ; leg_l3_joint
11 | (3,0) 0.90 ; leg_l4_joint
12 | (4,0) 0.53 ; leg_l5_joint
13 | (5,0) 0.00 ; leg_l6_joint
14 | (6,0) -0.05 ; leg_r1_joint
15 | (7,0) 0.0 ; leg_r2_joint
16 | (8,0) 0.37 ; leg_r3_joint
17 | (9,0) 0.90 ; leg_r4_joint
18 | (10,0) 0.53 ; leg_r5_joint
19 | (11,0) 0.00 ; leg_r6_joint
20 | }
21 |
22 | initialModeSchedule
23 | {
24 | modeSequence
25 | {
26 | [0] STANCE
27 | [1] STANCE
28 | }
29 | eventTimes
30 | {
31 | [0] 1000.0 ; not used
32 | }
33 | }
34 |
35 | defaultModeSequenceTemplate
36 | {
37 | modeSequence
38 | {
39 | [0] STANCE
40 | }
41 | switchingTimes
42 | {
43 | [0] 0.0
44 | [1] 1000.0
45 | }
46 | }
47 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/HumanoidPreComputation.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2020, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 |
35 | #include
36 | #include
37 |
38 | #include
39 |
40 | #include "humanoid_interface/common/ModelSettings.h"
41 | #include "humanoid_interface/constraint/EndEffectorLinearConstraint.h"
42 | #include "humanoid_interface/foot_planner/SwingTrajectoryPlanner.h"
43 |
44 | namespace ocs2 {
45 | namespace humanoid {
46 |
47 | /** Callback for caching and reference update */
48 | class HumanoidPreComputation : public PreComputation {
49 | public:
50 | HumanoidPreComputation(PinocchioInterface pinocchioInterface, CentroidalModelInfo info,
51 | const SwingTrajectoryPlanner& swingTrajectoryPlanner, ModelSettings settings);
52 | ~HumanoidPreComputation() override = default;
53 |
54 | HumanoidPreComputation* clone() const override;
55 |
56 | void request(RequestSet request, scalar_t t, const vector_t& x, const vector_t& u) override;
57 |
58 | const std::vector& getEeNormalVelocityConstraintConfigs() const { return eeNormalVelConConfigs_; }
59 |
60 | PinocchioInterface& getPinocchioInterface() { return pinocchioInterface_; }
61 | const PinocchioInterface& getPinocchioInterface() const { return pinocchioInterface_; }
62 |
63 | private:
64 | HumanoidPreComputation(const HumanoidPreComputation& other) = default;
65 |
66 | PinocchioInterface pinocchioInterface_;
67 | CentroidalModelInfo info_;
68 | const SwingTrajectoryPlanner* swingTrajectoryPlannerPtr_;
69 | const ModelSettings settings_;
70 |
71 | std::vector eeNormalVelConConfigs_;
72 | };
73 |
74 | } // namespace humanoid
75 | } // namespace ocs2
76 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/common/ModelSettings.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 | #include
35 |
36 | #include
37 |
38 | namespace ocs2 {
39 | namespace humanoid {
40 |
41 | struct ModelSettings {
42 | scalar_t positionErrorGain = 0.0;
43 |
44 | scalar_t phaseTransitionStanceTime = 0.4;
45 |
46 | bool verboseCppAd = true;
47 | bool recompileLibrariesCppAd = true;
48 | std::string modelFolderCppAd = "/tmp/ocs2";
49 |
50 | // This is only used to get names for the knees and to check urdf for extra joints that need to be fixed.
51 | std::vector jointNames{"leg_l1_joint", "leg_l2_joint", "leg_l3_joint", "leg_l4_joint", "leg_l5_joint", "leg_l6_joint",
52 | "leg_r1_joint", "leg_r2_joint", "leg_r3_joint", "leg_r4_joint", "leg_r5_joint", "leg_r6_joint"};
53 | std::vector contactNames6DoF{};
54 | std::vector contactNames3DoF{"l_foot_toe", "r_foot_toe", "l_foot_heel", "r_foot_heel"};
55 | };
56 |
57 | ModelSettings loadModelSettings(const std::string& filename, const std::string& fieldName = "model_settings", bool verbose = "true");
58 |
59 | } // namespace humanoid
60 | } // namespace ocs2
61 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/common/Types.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 |
35 | #include
36 |
37 | namespace ocs2 {
38 | namespace humanoid {
39 |
40 | template
41 | using feet_array_t = std::array;
42 | using contact_flag_t = feet_array_t;
43 |
44 | using vector3_t = Eigen::Matrix;
45 | using vector5_t = Eigen::Matrix;
46 | using vector6_t = Eigen::Matrix;
47 |
48 | using matrix3_t = Eigen::Matrix;
49 | using matrix35_t = Eigen::Matrix;
50 | using matrix65_t = Eigen::Matrix;
51 | using matrix56_t = Eigen::Matrix;
52 | using matrix66_t = Eigen::Matrix;
53 | using quaternion_t = Eigen::Quaternion;
54 |
55 | using vectorf_t = Eigen::Matrix;
56 | using vector3f_t = Eigen::Matrix;
57 | using vector5f_t = Eigen::Matrix;
58 | using vector6f_t = Eigen::Matrix;
59 |
60 | using matrixf_t = Eigen::Matrix;
61 | using matrix3f_t = Eigen::Matrix;
62 | using matrix35f_t = Eigen::Matrix;
63 | using matrix65f_t = Eigen::Matrix;
64 |
65 | } // namespace humanoid
66 | } // namespace ocs2
67 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/common/utils.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 | #include
35 | #include
36 |
37 | #include
38 | #include
39 |
40 | #include "humanoid_interface/common/Types.h"
41 |
42 | namespace ocs2 {
43 | namespace humanoid {
44 |
45 | /******************************************************************************************************/
46 | /******************************************************************************************************/
47 | /******************************************************************************************************/
48 | /** Counts contact feet */
49 | inline size_t numberOfClosedContacts(const contact_flag_t& contactFlags) {
50 | size_t numStanceLegs = 0;
51 | for (auto legInContact : contactFlags) {
52 | if (legInContact) {
53 | ++numStanceLegs;
54 | }
55 | }
56 | return numStanceLegs;
57 | }
58 |
59 | /******************************************************************************************************/
60 | /******************************************************************************************************/
61 | /******************************************************************************************************/
62 | /** Computes an input with zero joint velocity and forces which equally distribute the robot weight between contact feet. */
63 | inline vector_t weightCompensatingInput(const CentroidalModelInfoTpl& info, const contact_flag_t& contactFlags) {
64 | const auto numStanceLegs = numberOfClosedContacts(contactFlags);
65 | vector_t input = vector_t::Zero(info.inputDim);
66 | if (numStanceLegs > 0) {
67 | const scalar_t totalWeight = info.robotMass * 9.81;
68 | const vector3_t forceInInertialFrame(0.0, 0.0, totalWeight / numStanceLegs);
69 | for (size_t i = 0; i < contactFlags.size(); i++) {
70 | if (contactFlags[i]) {
71 | centroidal_model::getContactForces(input, i, info) = forceInInertialFrame;
72 | }
73 | } // end of i loop
74 | }
75 | return input;
76 | }
77 |
78 | } // namespace humanoid
79 | } // namespace ocs2
80 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/constraint/EndEffectorLinearConstraint.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 |
34 | #include
35 |
36 | #include
37 |
38 | namespace ocs2 {
39 | namespace humanoid {
40 |
41 | /**
42 | * Defines a linear constraint on an end-effector position (xee) and linear velocity (vee).
43 | * g(xee, vee) = Ax * xee + Av * vee + b
44 | * - For defining constraint of type g(xee), set Av to matrix_t(0, 0)
45 | * - For defining constraint of type g(vee), set Ax to matrix_t(0, 0)
46 | */
47 | class EndEffectorLinearConstraint final : public StateInputConstraint {
48 | public:
49 | /**
50 | * Coefficients of the linear constraints of the form:
51 | * g(xee, vee) = Ax * xee + Av * vee + b
52 | */
53 | struct Config {
54 | vector_t b;
55 | matrix_t Ax;
56 | matrix_t Av;
57 | };
58 |
59 | /**
60 | * Constructor
61 | * @param [in] endEffectorKinematics: The kinematic interface to the target end-effector.
62 | * @param [in] numConstraints: The number of constraints {1, 2, 3}
63 | * @param [in] config: The constraint coefficients, g(xee, vee) = Ax * xee + Av * vee + b
64 | */
65 | EndEffectorLinearConstraint(const EndEffectorKinematics& endEffectorKinematics, size_t numConstraints,
66 | Config config = Config());
67 |
68 | ~EndEffectorLinearConstraint() override = default;
69 | EndEffectorLinearConstraint* clone() const override { return new EndEffectorLinearConstraint(*this); }
70 |
71 | /** Sets a new constraint coefficients. */
72 | void configure(Config&& config);
73 | /** Sets a new constraint coefficients. */
74 | void configure(const Config& config) { this->configure(Config(config)); }
75 |
76 | /** Gets the underlying end-effector kinematics interface. */
77 | EndEffectorKinematics& getEndEffectorKinematics() { return *endEffectorKinematicsPtr_; }
78 |
79 | size_t getNumConstraints(scalar_t time) const override { return numConstraints_; }
80 | vector_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const PreComputation& preComp) const override;
81 | VectorFunctionLinearApproximation getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input,
82 | const PreComputation& preComp) const override;
83 |
84 | private:
85 | EndEffectorLinearConstraint(const EndEffectorLinearConstraint& rhs);
86 |
87 | std::unique_ptr> endEffectorKinematicsPtr_;
88 | const size_t numConstraints_;
89 | Config config_;
90 | };
91 |
92 | } // namespace humanoid
93 | } // namespace ocs2
94 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/constraint/FootRollConstraint.h:
--------------------------------------------------------------------------------
1 | /**
2 | * @file FootRollConstraint.h
3 | * @author xuejialong
4 | */
5 |
6 | #pragma once
7 |
8 | #include
9 |
10 | #include
11 |
12 | #include
13 |
14 | #include "humanoid_interface/reference_manager/SwitchedModelReferenceManager.h"
15 |
16 |
17 |
18 | namespace ocs2 {
19 | namespace humanoid {
20 |
21 | /**
22 | * Defines a linear constraint on an end-effector position (xee) and linear velocity (vee).
23 | * g(xee, vee) = Ax * xee + Av * vee + b
24 | * - For defining constraint of type g(xee), set Av to matrix_t(0, 0)
25 | * - For defining constraint of type g(vee), set Ax to matrix_t(0, 0)
26 | */
27 | class FootRollConstraint final : public StateInputConstraint {
28 | public:
29 |
30 | /**
31 | * Constructor
32 | * @param [in] endEffectorKinematics: The kinematic interface to the target end-effector.
33 | * @param [in] numConstraints: The number of constraints {1, 2, 3}
34 | */
35 | FootRollConstraint(const SwitchedModelReferenceManager& referenceManager, size_t contactPointIndex,
36 | CentroidalModelInfo info);
37 |
38 | ~FootRollConstraint() override = default;
39 | FootRollConstraint* clone() const override { return new FootRollConstraint(*this); }
40 |
41 | bool isActive(scalar_t time) const override;
42 | size_t getNumConstraints(scalar_t time) const override { return 1; }
43 | vector_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const PreComputation& preComp) const override;
44 | VectorFunctionLinearApproximation getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input,
45 | const PreComputation& preComp) const override;
46 |
47 | private:
48 | FootRollConstraint(const FootRollConstraint& rhs);
49 |
50 | const SwitchedModelReferenceManager* referenceManagerPtr_;
51 | const size_t contactPointIndex_;
52 | const CentroidalModelInfo info_;
53 | };
54 |
55 | } // namespace humanoid
56 | } // namespace ocs2
57 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/constraint/LeggedSelfCollisionConstraint.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by jialong xue on 23-1-29.
3 | //
4 |
5 | #pragma once
6 |
7 | #include
8 |
9 | #include "humanoid_interface/HumanoidPreComputation.h"
10 |
11 | namespace ocs2 {
12 | namespace humanoid {
13 | using namespace ocs2;
14 |
15 | class LeggedSelfCollisionConstraint final : public SelfCollisionConstraint {
16 | public:
17 | LeggedSelfCollisionConstraint(const CentroidalModelPinocchioMapping& mapping, PinocchioGeometryInterface pinocchioGeometryInterface,
18 | scalar_t minimumDistance)
19 | : SelfCollisionConstraint(mapping, std::move(pinocchioGeometryInterface), minimumDistance) {}
20 | ~LeggedSelfCollisionConstraint() override = default;
21 | LeggedSelfCollisionConstraint(const LeggedSelfCollisionConstraint& other) = default;
22 | LeggedSelfCollisionConstraint* clone() const override { return new LeggedSelfCollisionConstraint(*this); }
23 |
24 | const PinocchioInterface& getPinocchioInterface(const PreComputation& preComputation) const override {
25 | return cast(preComputation).getPinocchioInterface();
26 | }
27 | };
28 |
29 | } // namespace legged
30 | } // namespace ocs2
31 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/constraint/NormalVelocityConstraintCppAd.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 |
34 | #include "humanoid_interface/constraint/EndEffectorLinearConstraint.h"
35 | #include "humanoid_interface/reference_manager/SwitchedModelReferenceManager.h"
36 |
37 | namespace ocs2 {
38 | namespace humanoid {
39 |
40 | /**
41 | * Specializes the CppAd version of normal velocity constraint on an end-effector position and linear velocity.
42 | * Constructs the member EndEffectorLinearConstraint object with number of constraints of 1.
43 | *
44 | * See also EndEffectorLinearConstraint for the underlying computation.
45 | */
46 | class NormalVelocityConstraintCppAd final : public StateInputConstraint {
47 | public:
48 | /**
49 | * Constructor
50 | * @param [in] referenceManager : Switched model ReferenceManager
51 | * @param [in] endEffectorKinematics: The kinematic interface to the target end-effector.
52 | * @param [in] contactPointIndex : The 3 DoF contact index.
53 | */
54 | NormalVelocityConstraintCppAd(const SwitchedModelReferenceManager& referenceManager,
55 | const EndEffectorKinematics& endEffectorKinematics, size_t contactPointIndex);
56 |
57 | ~NormalVelocityConstraintCppAd() override = default;
58 | NormalVelocityConstraintCppAd* clone() const override { return new NormalVelocityConstraintCppAd(*this); }
59 |
60 | bool isActive(scalar_t time) const override;
61 | size_t getNumConstraints(scalar_t time) const override { return 1; }
62 | vector_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const PreComputation& preComp) const override;
63 | VectorFunctionLinearApproximation getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input,
64 | const PreComputation& preComp) const override;
65 |
66 | private:
67 | NormalVelocityConstraintCppAd(const NormalVelocityConstraintCppAd& rhs);
68 |
69 | const SwitchedModelReferenceManager* referenceManagerPtr_;
70 | std::unique_ptr eeLinearConstraintPtr_;
71 | const size_t contactPointIndex_;
72 | };
73 |
74 | } // namespace humanoid
75 | } // namespace ocs2
76 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/constraint/ZeroForceConstraint.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 |
35 | #include "humanoid_interface/reference_manager/SwitchedModelReferenceManager.h"
36 |
37 | namespace ocs2 {
38 | namespace humanoid {
39 |
40 | class ZeroForceConstraint final : public StateInputConstraint {
41 | public:
42 | /*
43 | * Constructor
44 | * @param [in] referenceManager : Switched model ReferenceManager.
45 | * @param [in] contactPointIndex : The 3 DoF contact index.
46 | * @param [in] info : The centroidal model information.
47 | */
48 | ZeroForceConstraint(const SwitchedModelReferenceManager& referenceManager, size_t contactPointIndex, CentroidalModelInfo info);
49 |
50 | ~ZeroForceConstraint() override = default;
51 | ZeroForceConstraint* clone() const override { return new ZeroForceConstraint(*this); }
52 |
53 | bool isActive(scalar_t time) const override;
54 | size_t getNumConstraints(scalar_t time) const override { return 3; }
55 | vector_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const PreComputation& preComp) const override;
56 | VectorFunctionLinearApproximation getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input,
57 | const PreComputation& preComp) const override;
58 |
59 | private:
60 | ZeroForceConstraint(const ZeroForceConstraint& other) = default;
61 |
62 | const SwitchedModelReferenceManager* referenceManagerPtr_;
63 | const size_t contactPointIndex_;
64 | const CentroidalModelInfo info_;
65 | };
66 |
67 | } // namespace humanoid
68 | } // namespace ocs2
69 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/constraint/ZeroVelocityConstraintCppAd.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 |
34 | #include "humanoid_interface/constraint/EndEffectorLinearConstraint.h"
35 | #include "humanoid_interface/reference_manager/SwitchedModelReferenceManager.h"
36 |
37 | namespace ocs2 {
38 | namespace humanoid {
39 |
40 | /**
41 | * Specializes the CppAd version of zero velocity constraint on an end-effector position and linear velocity.
42 | * Constructs the member EndEffectorLinearConstraint object with number of constraints of 3.
43 | *
44 | * See also EndEffectorLinearConstraint for the underlying computation.
45 | */
46 | class ZeroVelocityConstraintCppAd final : public StateInputConstraint {
47 | public:
48 | /**
49 | * Constructor
50 | * @param [in] referenceManager : Switched model ReferenceManager
51 | * @param [in] endEffectorKinematics: The kinematic interface to the target end-effector.
52 | * @param [in] contactPointIndex : The 3 DoF contact index.
53 | * @param [in] config: The constraint coefficients
54 | */
55 | ZeroVelocityConstraintCppAd(const SwitchedModelReferenceManager& referenceManager,
56 | const EndEffectorKinematics& endEffectorKinematics, size_t contactPointIndex,
57 | EndEffectorLinearConstraint::Config config = EndEffectorLinearConstraint::Config());
58 |
59 | ~ZeroVelocityConstraintCppAd() override = default;
60 | ZeroVelocityConstraintCppAd* clone() const override { return new ZeroVelocityConstraintCppAd(*this); }
61 |
62 | bool isActive(scalar_t time) const override;
63 | size_t getNumConstraints(scalar_t time) const override { return 3; }
64 | vector_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const PreComputation& preComp) const override;
65 | VectorFunctionLinearApproximation getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input,
66 | const PreComputation& preComp) const override;
67 |
68 | private:
69 | ZeroVelocityConstraintCppAd(const ZeroVelocityConstraintCppAd& rhs);
70 |
71 | const SwitchedModelReferenceManager* referenceManagerPtr_;
72 | std::unique_ptr eeLinearConstraintPtr_;
73 | const size_t contactPointIndex_;
74 | };
75 |
76 | } // namespace humanoid
77 | } // namespace ocs2
78 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/cost/HumanoidQuadraticTrackingCost.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 | #include
35 |
36 | #include "humanoid_interface/common/utils.h"
37 | #include "humanoid_interface/reference_manager/SwitchedModelReferenceManager.h"
38 |
39 | namespace ocs2 {
40 | namespace humanoid {
41 |
42 | /**
43 | * State-input tracking cost used for intermediate times
44 | */
45 | class HumanoidStateInputQuadraticCost final : public QuadraticStateInputCost {
46 | public:
47 | HumanoidStateInputQuadraticCost(matrix_t Q, matrix_t R, CentroidalModelInfo info,
48 | const SwitchedModelReferenceManager& referenceManager)
49 | : QuadraticStateInputCost(std::move(Q), std::move(R)), info_(std::move(info)), referenceManagerPtr_(&referenceManager) {}
50 |
51 | ~HumanoidStateInputQuadraticCost() override = default;
52 | HumanoidStateInputQuadraticCost* clone() const override { return new HumanoidStateInputQuadraticCost(*this); }
53 |
54 | private:
55 | HumanoidStateInputQuadraticCost(const HumanoidStateInputQuadraticCost& rhs) = default;
56 |
57 | std::pair getStateInputDeviation(scalar_t time, const vector_t& state, const vector_t& input,
58 | const TargetTrajectories& targetTrajectories) const override {
59 | const auto contactFlags = referenceManagerPtr_->getContactFlags(time);
60 | const vector_t xNominal = targetTrajectories.getDesiredState(time);
61 | const vector_t uNominal = weightCompensatingInput(info_, contactFlags);
62 | return {state - xNominal, input - uNominal};
63 | }
64 |
65 | const CentroidalModelInfo info_;
66 | const SwitchedModelReferenceManager* referenceManagerPtr_;
67 | };
68 |
69 | /**
70 | * State tracking cost used for the final time
71 | */
72 | class HumanoidStateQuadraticCost final : public QuadraticStateCost {
73 | public:
74 | HumanoidStateQuadraticCost(matrix_t Q, CentroidalModelInfo info, const SwitchedModelReferenceManager& referenceManager)
75 | : QuadraticStateCost(std::move(Q)), info_(std::move(info)), referenceManagerPtr_(&referenceManager) {}
76 |
77 | ~HumanoidStateQuadraticCost() override = default;
78 | HumanoidStateQuadraticCost* clone() const override { return new HumanoidStateQuadraticCost(*this); }
79 |
80 | private:
81 | HumanoidStateQuadraticCost(const HumanoidStateQuadraticCost& rhs) = default;
82 |
83 | vector_t getStateDeviation(scalar_t time, const vector_t& state, const TargetTrajectories& targetTrajectories) const override {
84 | const auto contactFlags = referenceManagerPtr_->getContactFlags(time);
85 | const vector_t xNominal = targetTrajectories.getDesiredState(time);
86 | return state - xNominal;
87 | }
88 |
89 | const CentroidalModelInfo info_;
90 | const SwitchedModelReferenceManager* referenceManagerPtr_;
91 | };
92 |
93 | } // namespace humanoid
94 | } // namespace ocs2
95 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/dynamics/HumanoidDynamicsAD.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 |
34 | #include
35 | #include
36 |
37 | #include "humanoid_interface/common/ModelSettings.h"
38 |
39 | namespace ocs2 {
40 | namespace humanoid {
41 |
42 | class HumanoidDynamicsAD final : public SystemDynamicsBase {
43 | public:
44 | HumanoidDynamicsAD(const PinocchioInterface& pinocchioInterface, const CentroidalModelInfo& info, const std::string& modelName,
45 | const ModelSettings& modelSettings);
46 |
47 | ~HumanoidDynamicsAD() override = default;
48 | HumanoidDynamicsAD* clone() const override { return new HumanoidDynamicsAD(*this); }
49 |
50 | vector_t computeFlowMap(scalar_t time, const vector_t& state, const vector_t& input, const PreComputation& preComp) override;
51 | VectorFunctionLinearApproximation linearApproximation(scalar_t time, const vector_t& state, const vector_t& input,
52 | const PreComputation& preComp) override;
53 |
54 | private:
55 | HumanoidDynamicsAD(const HumanoidDynamicsAD& rhs) = default;
56 |
57 | PinocchioCentroidalDynamicsAD pinocchioCentroidalDynamicsAd_;
58 | };
59 |
60 | } // namespace humanoid
61 | } // namespace ocs2
62 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/foot_planner/CubicSpline.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 |
34 | namespace ocs2 {
35 | namespace humanoid {
36 |
37 | class CubicSpline {
38 | public:
39 | struct Node {
40 | scalar_t time;
41 | scalar_t position;
42 | scalar_t velocity;
43 | };
44 |
45 | CubicSpline(Node start, Node end);
46 |
47 | scalar_t position(scalar_t time) const;
48 |
49 | scalar_t velocity(scalar_t time) const;
50 |
51 | scalar_t acceleration(scalar_t time) const;
52 |
53 | scalar_t startTimeDerivative(scalar_t t) const;
54 |
55 | scalar_t finalTimeDerivative(scalar_t t) const;
56 |
57 | private:
58 | scalar_t normalizedTime(scalar_t t) const;
59 |
60 | scalar_t t0_;
61 | scalar_t t1_;
62 | scalar_t dt_;
63 |
64 | scalar_t c0_;
65 | scalar_t c1_;
66 | scalar_t c2_;
67 | scalar_t c3_;
68 |
69 | scalar_t dc0_; // derivative w.r.t. dt_
70 | scalar_t dc1_; // derivative w.r.t. dt_
71 | scalar_t dc2_; // derivative w.r.t. dt_
72 | scalar_t dc3_; // derivative w.r.t. dt_
73 | };
74 |
75 | } // namespace humanoid
76 | } // namespace ocs2
77 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/foot_planner/SplineCpg.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include "humanoid_interface/foot_planner/CubicSpline.h"
33 |
34 | namespace ocs2 {
35 | namespace humanoid {
36 |
37 | class SplineCpg {
38 | public:
39 | SplineCpg(CubicSpline::Node liftOff, scalar_t midHeight, CubicSpline::Node touchDown);
40 |
41 | scalar_t position(scalar_t time) const;
42 |
43 | scalar_t velocity(scalar_t time) const;
44 |
45 | scalar_t acceleration(scalar_t time) const;
46 |
47 | scalar_t startTimeDerivative(scalar_t time) const;
48 |
49 | scalar_t finalTimeDerivative(scalar_t time) const;
50 |
51 | private:
52 | scalar_t midTime_;
53 | CubicSpline leftSpline_;
54 | CubicSpline rightSpline_;
55 | };
56 |
57 | } // namespace humanoid
58 | } // namespace ocs2
59 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/gait/Gait.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 |
35 | #include
36 |
37 | namespace ocs2 {
38 | namespace humanoid {
39 |
40 | /**
41 | * A gait is a periodic mode schedule parameterized by a "phase" variable.
42 | *
43 | * The eventPhases only indicate switches of modes, i.e. phase = 0 and phase = 1 are not part of the eventPhases.
44 | * The number of modes is therefore number of phases + 1
45 | *
46 | * The conversion to time is regulated by a duration
47 | */
48 | struct Gait {
49 | /** time for one gait cycle*/
50 | scalar_t duration;
51 | /** points in (0.0, 1.0) along the gait cycle where the contact mode changes, size N-1 */
52 | std::vector eventPhases;
53 | /** sequence of contact modes, size: N */
54 | std::vector modeSequence;
55 | };
56 |
57 | /**
58 | * isValidGait checks the following properties
59 | * - positive duration
60 | * - eventPhases are all in (0.0, 1.0)
61 | * - eventPhases are sorted
62 | * - the size of the modeSequences is 1 more than the eventPhases.
63 | */
64 | bool isValidGait(const Gait& gait);
65 |
66 | /** Check is if the phase is in [0.0, 1.0) */
67 | bool isValidPhase(scalar_t phase);
68 |
69 | /** Wraps a phase to [0.0, 1.0) */
70 | scalar_t wrapPhase(scalar_t phase);
71 |
72 | /** The modes are selected with a closed-open interval: [ ) */
73 | int getModeIndexFromPhase(scalar_t phase, const Gait& gait);
74 |
75 | /** Gets the active mode from the phase variable */
76 | size_t getModeFromPhase(scalar_t phase, const Gait& gait);
77 |
78 | /** Returns the time left in the gait based on the phase variable */
79 | scalar_t timeLeftInGait(scalar_t phase, const Gait& gait);
80 |
81 | /** Returns the time left in the current based on the phase variable */
82 | scalar_t timeLeftInMode(scalar_t phase, const Gait& gait);
83 |
84 | /** Print gait */
85 | std::ostream& operator<<(std::ostream& stream, const Gait& gait);
86 |
87 | } // namespace humanoid
88 | } // namespace ocs2
89 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/gait/GaitSchedule.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 |
34 | #include
35 | #include
36 |
37 | #include "humanoid_interface/gait/ModeSequenceTemplate.h"
38 |
39 | namespace ocs2 {
40 | namespace humanoid {
41 |
42 | class GaitSchedule {
43 | public:
44 | GaitSchedule(ModeSchedule initModeSchedule, ModeSequenceTemplate initModeSequenceTemplate, scalar_t phaseTransitionStanceTime);
45 |
46 | /**
47 | * Sets the mode schedule.
48 | *
49 | * @param [in] modeSchedule: The mode schedule to be used.
50 | */
51 | void setModeSchedule(const ModeSchedule& modeSchedule) { modeSchedule_ = modeSchedule; }
52 |
53 | /**
54 | * Gets the mode schedule.
55 | *
56 | * @param [in] lowerBoundTime: The smallest time for which the ModeSchedule should be defined.
57 | * @param [in] upperBoundTime: The greatest time for which the ModeSchedule should be defined.
58 | */
59 | ModeSchedule getModeSchedule(scalar_t lowerBoundTime, scalar_t upperBoundTime);
60 |
61 | /**
62 | * Used to insert a new user defined logic in the given time period.
63 | *
64 | * @param [in] startTime: The initial time from which the new mode sequence template should start.
65 | * @param [in] finalTime: The final time until when the new mode sequence needs to be defined.
66 | */
67 | void insertModeSequenceTemplate(const ModeSequenceTemplate& modeSequenceTemplate, scalar_t startTime, scalar_t finalTime);
68 |
69 | private:
70 | /**
71 | * Extends the switch information from lowerBoundTime to upperBoundTime based on the template mode sequence.
72 | *
73 | * @param [in] startTime: The initial time from which the mode schedule should be appended with the template.
74 | * @param [in] finalTime: The final time to which the mode schedule should be appended with the template.
75 | */
76 | void tileModeSequenceTemplate(scalar_t startTime, scalar_t finalTime);
77 |
78 | private:
79 | ModeSchedule modeSchedule_;
80 | ModeSequenceTemplate modeSequenceTemplate_;
81 | scalar_t phaseTransitionStanceTime_;
82 | };
83 |
84 | } // namespace humanoid
85 | } // namespace ocs2
86 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/initialization/HumanoidInitializer.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 |
35 | #include "humanoid_interface/reference_manager/SwitchedModelReferenceManager.h"
36 |
37 | namespace ocs2 {
38 | namespace humanoid {
39 |
40 | class HumanoidInitializer final : public Initializer {
41 | public:
42 | /*
43 | * Constructor
44 | * @param [in] info : The centroidal model information.
45 | * @param [in] referenceManager : Switched system reference manager.
46 | * @param [in] extendNormalizedMomentum: If true, it extrapolates the normalized momenta; otherwise sets them to zero.
47 | */
48 | HumanoidInitializer(CentroidalModelInfo info, const SwitchedModelReferenceManager& referenceManager,
49 | bool extendNormalizedMomentum = false);
50 |
51 | ~HumanoidInitializer() override = default;
52 | HumanoidInitializer* clone() const override;
53 |
54 | void compute(scalar_t time, const vector_t& state, scalar_t nextTime, vector_t& input, vector_t& nextState) override;
55 |
56 | private:
57 | HumanoidInitializer(const HumanoidInitializer& other) = default;
58 |
59 | const CentroidalModelInfo info_;
60 | const SwitchedModelReferenceManager* referenceManagerPtr_;
61 | const bool extendNormalizedMomentum_;
62 | };
63 |
64 | } // namespace humanoid
65 | } // namespace ocs2
66 |
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/package_path.h.in:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 |
35 | namespace ocs2 {
36 | namespace humanoid {
37 |
38 | /** Gets the path to the package source directory. */
39 | inline std::string getPath() {
40 | return "@PROJECT_SOURCE_DIR@";
41 | }
42 |
43 | } // namespace humanoid
44 | } // namespace ocs2
--------------------------------------------------------------------------------
/humanoid_interface/include/humanoid_interface/reference_manager/SwitchedModelReferenceManager.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 | #include
34 |
35 | #include "humanoid_interface/foot_planner/SwingTrajectoryPlanner.h"
36 | #include "humanoid_interface/gait/GaitSchedule.h"
37 | #include "humanoid_interface/gait/MotionPhaseDefinition.h"
38 |
39 | namespace ocs2 {
40 | namespace humanoid {
41 |
42 | /**
43 | * Manages the ModeSchedule and the TargetTrajectories for switched model.
44 | */
45 | class SwitchedModelReferenceManager : public ReferenceManager {
46 | public:
47 | SwitchedModelReferenceManager(std::shared_ptr gaitSchedulePtr, std::shared_ptr swingTrajectoryPtr);
48 |
49 | ~SwitchedModelReferenceManager() override = default;
50 |
51 | void setModeSchedule(const ModeSchedule& modeSchedule) override;
52 |
53 | contact_flag_t getContactFlags(scalar_t time) const;
54 |
55 | const std::shared_ptr& getGaitSchedule() { return gaitSchedulePtr_; }
56 |
57 | const std::shared_ptr& getSwingTrajectoryPlanner() { return swingTrajectoryPtr_; }
58 |
59 | private:
60 | void modifyReferences(scalar_t initTime, scalar_t finalTime, const vector_t& initState, TargetTrajectories& targetTrajectories,
61 | ModeSchedule& modeSchedule) override;
62 |
63 | std::shared_ptr gaitSchedulePtr_;
64 | std::shared_ptr swingTrajectoryPtr_;
65 | };
66 |
67 | } // namespace humanoid
68 | } // namespace ocs2
69 |
--------------------------------------------------------------------------------
/humanoid_interface/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | humanoid_interface
4 | 0.0.1
5 | The humanoid_interface package
6 |
7 | Jialong Xue
8 |
9 | BSD-3
10 |
11 | ament_cmake
12 |
13 | ocs2_core
14 | ocs2_oc
15 | ocs2_ddp
16 | ocs2_mpc
17 | ocs2_sqp
18 | ocs2_ipm
19 | ocs2_robotic_assets
20 | ocs2_robotic_tools
21 | ocs2_pinocchio_interface
22 | ocs2_centroidal_model
23 | ocs2_self_collision
24 | pinocchio
25 |
26 | ament_cmake_gtest
27 |
28 | ament_cmake
29 |
30 |
31 |
32 |
33 |
--------------------------------------------------------------------------------
/humanoid_interface/src/HumanoidPreComputation.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2020, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include
31 |
32 | #include
33 | #include
34 | #include
35 |
36 | #include
37 |
38 | #include
39 |
40 | namespace ocs2 {
41 | namespace humanoid {
42 |
43 | /******************************************************************************************************/
44 | /******************************************************************************************************/
45 | /******************************************************************************************************/
46 | HumanoidPreComputation::HumanoidPreComputation(PinocchioInterface pinocchioInterface, CentroidalModelInfo info,
47 | const SwingTrajectoryPlanner& swingTrajectoryPlanner, ModelSettings settings)
48 | : pinocchioInterface_(std::move(pinocchioInterface)),
49 | info_(std::move(info)),
50 | swingTrajectoryPlannerPtr_(&swingTrajectoryPlanner),
51 | settings_(std::move(settings)) {
52 | eeNormalVelConConfigs_.resize(info_.numThreeDofContacts);
53 | }
54 |
55 | /******************************************************************************************************/
56 | /******************************************************************************************************/
57 | /******************************************************************************************************/
58 | HumanoidPreComputation* HumanoidPreComputation::clone() const {
59 | return new HumanoidPreComputation(*this);
60 | }
61 |
62 | /******************************************************************************************************/
63 | /******************************************************************************************************/
64 | /******************************************************************************************************/
65 | void HumanoidPreComputation::request(RequestSet request, scalar_t t, const vector_t& x, const vector_t& u) {
66 | if (!request.containsAny(Request::Cost + Request::Constraint + Request::SoftConstraint)) {
67 | return;
68 | }
69 |
70 | // lambda to set config for normal velocity constraints
71 | auto eeNormalVelConConfig = [&](size_t footIndex) {
72 | EndEffectorLinearConstraint::Config config;
73 | config.b = (vector_t(1) << -swingTrajectoryPlannerPtr_->getZvelocityConstraint(footIndex, t)).finished();
74 | config.Av = (matrix_t(1, 3) << 0.0, 0.0, 1.0).finished();
75 | if (!numerics::almost_eq(settings_.positionErrorGain, 0.0)) {
76 | config.b(0) -= settings_.positionErrorGain * swingTrajectoryPlannerPtr_->getZpositionConstraint(footIndex, t);
77 | config.Ax = (matrix_t(1, 3) << 0.0, 0.0, settings_.positionErrorGain).finished();
78 | }
79 | return config;
80 | };
81 |
82 | if (request.contains(Request::Constraint)) {
83 | for (size_t i = 0; i < info_.numThreeDofContacts; i++) {
84 | eeNormalVelConConfigs_[i] = eeNormalVelConConfig(i);
85 | }
86 | }
87 | }
88 |
89 | } // namespace humanoid
90 | } // namespace ocs2
91 |
--------------------------------------------------------------------------------
/humanoid_interface/src/common/ModelSettings.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include "humanoid_interface/common/ModelSettings.h"
31 |
32 | #include
33 | #include
34 |
35 | #include
36 |
37 | namespace ocs2 {
38 | namespace humanoid {
39 |
40 | ModelSettings loadModelSettings(const std::string& filename, const std::string& fieldName, bool verbose) {
41 | ModelSettings modelSettings;
42 |
43 | boost::property_tree::ptree pt;
44 | boost::property_tree::read_info(filename, pt);
45 |
46 | if (verbose) {
47 | std::cerr << "\n #### Legged Robot Model Settings:";
48 | std::cerr << "\n #### =============================================================================\n";
49 | }
50 |
51 | loadData::loadPtreeValue(pt, modelSettings.positionErrorGain, fieldName + ".positionErrorGain", verbose);
52 |
53 | loadData::loadPtreeValue(pt, modelSettings.phaseTransitionStanceTime, fieldName + ".phaseTransitionStanceTime", verbose);
54 | loadData::loadPtreeValue(pt, modelSettings.verboseCppAd, fieldName + ".verboseCppAd", verbose);
55 | loadData::loadPtreeValue(pt, modelSettings.recompileLibrariesCppAd, fieldName + ".recompileLibrariesCppAd", verbose);
56 | loadData::loadPtreeValue(pt, modelSettings.modelFolderCppAd, fieldName + ".modelFolderCppAd", verbose);
57 |
58 | if (verbose) {
59 | std::cerr << " #### =============================================================================" << std::endl;
60 | }
61 | return modelSettings;
62 | }
63 |
64 | } // namespace humanoid
65 | } // namespace ocs2
66 |
--------------------------------------------------------------------------------
/humanoid_interface/src/constraint/FootRollContraint.cpp:
--------------------------------------------------------------------------------
1 | //
2 | // Created by pocket on 24-2-4.
3 | //
4 | #include "humanoid_interface/constraint/FootRollConstraint.h"
5 |
6 | #include
7 |
8 | namespace ocs2 {
9 | namespace humanoid {
10 | FootRollConstraint::FootRollConstraint(const SwitchedModelReferenceManager& referenceManager, size_t contactPointIndex,CentroidalModelInfo info)
11 | : StateInputConstraint(ConstraintOrder::Linear),
12 | referenceManagerPtr_(&referenceManager),
13 | contactPointIndex_(contactPointIndex),
14 | info_(std::move(info)) {}
15 |
16 | FootRollConstraint::FootRollConstraint(const FootRollConstraint& rhs)
17 | : StateInputConstraint(rhs),
18 | referenceManagerPtr_(rhs.referenceManagerPtr_),
19 | contactPointIndex_(rhs.contactPointIndex_),
20 | info_(rhs.info_) {}
21 |
22 | bool FootRollConstraint::isActive(scalar_t time) const {
23 | // return !referenceManagerPtr_->getContactFlags(time)[contactPointIndex_];
24 | return true;
25 | }
26 |
27 |
28 | vector_t FootRollConstraint::getValue(scalar_t time, const vector_t& state, const vector_t& input,
29 | const PreComputation& preComp) const {
30 | //获取最后一个关节的速度
31 | long index = 5 + (contactPointIndex_) * 6;
32 | return centroidal_model::getJointVelocities(input, info_).block<-1, 1>(index, 0, 1, 1);
33 | }
34 |
35 |
36 | VectorFunctionLinearApproximation FootRollConstraint::getLinearApproximation(scalar_t time, const vector_t& state,
37 | const vector_t& input,
38 | const PreComputation& preComp) const {
39 | VectorFunctionLinearApproximation approx;
40 | approx.f = getValue(time, state, input, preComp);
41 | approx.dfdx = matrix_t::Zero(1, state.size());
42 | approx.dfdu = matrix_t::Zero(1, input.size());
43 | approx.dfdu.middleCols<1>(17 + (contactPointIndex_ ) * 6).diagonal() = vector_t::Ones(1);
44 | return approx;
45 | }
46 | }
47 | }
48 |
--------------------------------------------------------------------------------
/humanoid_interface/src/constraint/ZeroForceConstraint.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include "humanoid_interface/constraint/ZeroForceConstraint.h"
31 |
32 | #include
33 |
34 | namespace ocs2 {
35 | namespace humanoid {
36 |
37 | /******************************************************************************************************/
38 | /******************************************************************************************************/
39 | /******************************************************************************************************/
40 | ZeroForceConstraint::ZeroForceConstraint(const SwitchedModelReferenceManager& referenceManager, size_t contactPointIndex,
41 | CentroidalModelInfo info)
42 | : StateInputConstraint(ConstraintOrder::Linear),
43 | referenceManagerPtr_(&referenceManager),
44 | contactPointIndex_(contactPointIndex),
45 | info_(std::move(info)) {}
46 |
47 | /******************************************************************************************************/
48 | /******************************************************************************************************/
49 | /******************************************************************************************************/
50 | bool ZeroForceConstraint::isActive(scalar_t time) const {
51 | return !referenceManagerPtr_->getContactFlags(time)[contactPointIndex_];
52 | }
53 |
54 | /******************************************************************************************************/
55 | /******************************************************************************************************/
56 | /******************************************************************************************************/
57 | vector_t ZeroForceConstraint::getValue(scalar_t time, const vector_t& state, const vector_t& input, const PreComputation& preComp) const {
58 | return centroidal_model::getContactForces(input, contactPointIndex_, info_);
59 | }
60 |
61 | /******************************************************************************************************/
62 | /******************************************************************************************************/
63 | /******************************************************************************************************/
64 | VectorFunctionLinearApproximation ZeroForceConstraint::getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input,
65 | const PreComputation& preComp) const {
66 | VectorFunctionLinearApproximation approx;
67 | approx.f = getValue(time, state, input, preComp);
68 | approx.dfdx = matrix_t::Zero(3, state.size());
69 | approx.dfdu = matrix_t::Zero(3, input.size());
70 | approx.dfdu.middleCols<3>(3 * contactPointIndex_).diagonal() = vector_t::Ones(3);
71 | return approx;
72 | }
73 |
74 | } // namespace humanoid
75 | } // namespace ocs2
76 |
--------------------------------------------------------------------------------
/humanoid_interface/src/dynamics/HumanoidDynamicsAD.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include "humanoid_interface/dynamics/HumanoidDynamicsAD.h"
31 |
32 | namespace ocs2 {
33 | namespace humanoid {
34 |
35 | /******************************************************************************************************/
36 | /******************************************************************************************************/
37 | /******************************************************************************************************/
38 | HumanoidDynamicsAD::HumanoidDynamicsAD(const PinocchioInterface& pinocchioInterface, const CentroidalModelInfo& info,
39 | const std::string& modelName, const ModelSettings& modelSettings)
40 | : pinocchioCentroidalDynamicsAd_(pinocchioInterface, info, modelName, modelSettings.modelFolderCppAd,
41 | modelSettings.recompileLibrariesCppAd, modelSettings.verboseCppAd) {}
42 |
43 | /******************************************************************************************************/
44 | /******************************************************************************************************/
45 | /******************************************************************************************************/
46 | vector_t HumanoidDynamicsAD::computeFlowMap(scalar_t time, const vector_t& state, const vector_t& input, const PreComputation& preComp) {
47 | return pinocchioCentroidalDynamicsAd_.getValue(time, state, input);
48 | }
49 |
50 | /******************************************************************************************************/
51 | /******************************************************************************************************/
52 | /******************************************************************************************************/
53 | VectorFunctionLinearApproximation HumanoidDynamicsAD::linearApproximation(scalar_t time, const vector_t& state, const vector_t& input,
54 | const PreComputation& preComp) {
55 | return pinocchioCentroidalDynamicsAd_.getLinearApproximation(time, state, input);
56 | }
57 |
58 | } // namespace humanoid
59 | } // namespace ocs2
60 |
--------------------------------------------------------------------------------
/humanoid_interface/src/initialization/HumanoidInitializer.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include "humanoid_interface/initialization/HumanoidInitializer.h"
31 |
32 | #include "humanoid_interface/common/utils.h"
33 |
34 | #include
35 |
36 | namespace ocs2 {
37 | namespace humanoid {
38 |
39 | /******************************************************************************************************/
40 | /******************************************************************************************************/
41 | /******************************************************************************************************/
42 | HumanoidInitializer::HumanoidInitializer(CentroidalModelInfo info, const SwitchedModelReferenceManager& referenceManager,
43 | bool extendNormalizedMomentum)
44 | : info_(std::move(info)), referenceManagerPtr_(&referenceManager), extendNormalizedMomentum_(extendNormalizedMomentum) {}
45 |
46 | /******************************************************************************************************/
47 | /******************************************************************************************************/
48 | /******************************************************************************************************/
49 | HumanoidInitializer* HumanoidInitializer::clone() const {
50 | return new HumanoidInitializer(*this);
51 | }
52 |
53 | /******************************************************************************************************/
54 | /******************************************************************************************************/
55 | /******************************************************************************************************/
56 | void HumanoidInitializer::compute(scalar_t time, const vector_t& state, scalar_t nextTime, vector_t& input, vector_t& nextState) {
57 | const auto contactFlags = referenceManagerPtr_->getContactFlags(time);
58 | input = weightCompensatingInput(info_, contactFlags);
59 | nextState = state;
60 | if (!extendNormalizedMomentum_) {
61 | centroidal_model::getNormalizedMomentum(nextState, info_).setZero();
62 | }
63 | }
64 |
65 | } // namespace humanoid
66 | } // namespace ocs2
67 |
--------------------------------------------------------------------------------
/humanoid_interface/src/reference_manager/SwitchedModelReferenceManager.cpp:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #include "humanoid_interface/reference_manager/SwitchedModelReferenceManager.h"
31 |
32 | namespace ocs2 {
33 | namespace humanoid {
34 |
35 | /******************************************************************************************************/
36 | /******************************************************************************************************/
37 | /******************************************************************************************************/
38 | SwitchedModelReferenceManager::SwitchedModelReferenceManager(std::shared_ptr gaitSchedulePtr,
39 | std::shared_ptr swingTrajectoryPtr)
40 | : ReferenceManager(TargetTrajectories(), ModeSchedule()),
41 | gaitSchedulePtr_(std::move(gaitSchedulePtr)),
42 | swingTrajectoryPtr_(std::move(swingTrajectoryPtr)) {}
43 |
44 | /******************************************************************************************************/
45 | /******************************************************************************************************/
46 | /******************************************************************************************************/
47 | void SwitchedModelReferenceManager::setModeSchedule(const ModeSchedule& modeSchedule) {
48 | ReferenceManager::setModeSchedule(modeSchedule);
49 | gaitSchedulePtr_->setModeSchedule(modeSchedule);
50 | }
51 |
52 | /******************************************************************************************************/
53 | /******************************************************************************************************/
54 | /******************************************************************************************************/
55 | contact_flag_t SwitchedModelReferenceManager::getContactFlags(scalar_t time) const {
56 | return modeNumber2StanceLeg(this->getModeSchedule().modeAtTime(time));
57 | }
58 |
59 | /******************************************************************************************************/
60 | /******************************************************************************************************/
61 | /******************************************************************************************************/
62 | void SwitchedModelReferenceManager::modifyReferences(scalar_t initTime, scalar_t finalTime, const vector_t& initState,
63 | TargetTrajectories& targetTrajectories, ModeSchedule& modeSchedule) {
64 | const auto timeHorizon = finalTime - initTime;
65 | modeSchedule = gaitSchedulePtr_->getModeSchedule(initTime - timeHorizon, finalTime + timeHorizon);
66 |
67 | const scalar_t terrainHeight = 0.0;
68 | swingTrajectoryPtr_->update(modeSchedule, terrainHeight);
69 | }
70 |
71 | } // namespace humanoid
72 | } // namespace ocs2
73 |
--------------------------------------------------------------------------------
/humanoid_interface/test/include/humanoid_interface/test/AnymalFactoryFunctions.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | Copyright (c) 2021, Farbod Farshidian. All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 |
7 | * Redistributions of source code must retain the above copyright notice, this
8 | list of conditions and the following disclaimer.
9 |
10 | * Redistributions in binary form must reproduce the above copyright notice,
11 | this list of conditions and the following disclaimer in the documentation
12 | and/or other materials provided with the distribution.
13 |
14 | * Neither the name of the copyright holder nor the names of its
15 | contributors may be used to endorse or promote products derived from
16 | this software without specific prior written permission.
17 |
18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 | ******************************************************************************/
29 |
30 | #pragma once
31 |
32 | #include
33 |
34 | #include
35 | #include