Skip to content

Commit

Permalink
Merged in feature/interior_point_example (pull request #686)
Browse files Browse the repository at this point in the history
add IPM legged robot example

Approved-by: Farbod Farshidian
  • Loading branch information
mayataka authored and farbod-farshidian committed Dec 18, 2022
2 parents 922c649 + 1eac5b6 commit 3fba74e
Show file tree
Hide file tree
Showing 13 changed files with 548 additions and 17 deletions.
2 changes: 1 addition & 1 deletion ocs2_ipm/src/IpmHelpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ scalar_t fractionToBoundaryStepSize(const vector_t& v, const vector_t& dv, scala

const vector_t invFractionToBoundary = (-1.0 / marginRate) * dv.cwiseQuotient(v);
const auto alpha = invFractionToBoundary.maxCoeff();
return alpha > 0.0? std::min(1.0 / alpha, 1.0): 1.0;
return alpha > 0.0 ? std::min(1.0 / alpha, 1.0) : 1.0;
}

} // namespace ipm
Expand Down
1 change: 1 addition & 0 deletions ocs2_robotic_examples/ocs2_legged_robot/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ set(CATKIN_PACKAGE_DEPENDENCIES
ocs2_ddp
ocs2_mpc
ocs2_sqp
ocs2_ipm
ocs2_robotic_tools
ocs2_pinocchio_interface
ocs2_centroidal_model
Expand Down
33 changes: 33 additions & 0 deletions ocs2_robotic_examples/ocs2_legged_robot/config/mpc/task.info
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,39 @@ sqp
threadPriority 50
}

; Multiple_Shooting IPM settings
ipm
{
nThreads 3
dt 0.015
ipmIteration 1
deltaTol 1e-4
g_max 10.0
g_min 1e-6
computeLagrangeMultipliers true
printSolverStatistics true
printSolverStatus false
printLinesearch false
useFeedbackPolicy true
integratorType RK2
threadPriority 50

initialBarrierParameter 1e-4
targetBarrierParameter 1e-4
barrierLinearDecreaseFactor 0.2
barrierSuperlinearDecreasePower 1.5
barrierReductionCostTol 1e-3
barrierReductionConstraintTol 1e-3

fractionToBoundaryMargin 0.995
usePrimalStepSizeForDual false

initialSlackLowerBound 1e-4
initialDualLowerBound 1e-4
initialSlackMarginRate 1e-2
initialDualMarginRate 1e-2
}

; DDP settings
ddp
{
Expand Down

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#include <ocs2_core/Types.h>
#include <ocs2_core/penalties/Penalties.h>
#include <ocs2_ddp/DDP_Settings.h>
#include <ocs2_ipm/IpmSettings.h>
#include <ocs2_mpc/MPC_Settings.h>
#include <ocs2_oc/rollout/TimeTriggeredRollout.h>
#include <ocs2_pinocchio_interface/PinocchioInterface.h>
Expand Down Expand Up @@ -62,8 +63,10 @@ class LeggedRobotInterface final : public RobotInterface {
* @param [in] taskFile: The absolute path to the configuration file for the MPC.
* @param [in] urdfFile: The absolute path to the URDF file for the robot.
* @param [in] referenceFile: The absolute path to the reference configuration file.
* @param [in] useHardFrictionConeConstraint: Which to use hard or soft friction cone constraints.
*/
LeggedRobotInterface(const std::string& taskFile, const std::string& urdfFile, const std::string& referenceFile);
LeggedRobotInterface(const std::string& taskFile, const std::string& urdfFile, const std::string& referenceFile,
bool useHardFrictionConeConstraint = false);

~LeggedRobotInterface() override = default;

Expand All @@ -74,6 +77,7 @@ class LeggedRobotInterface final : public RobotInterface {
const mpc::Settings& mpcSettings() const { return mpcSettings_; }
const rollout::Settings& rolloutSettings() const { return rolloutSettings_; }
const sqp::Settings& sqpSettings() { return sqpSettings_; }
const ipm::Settings& ipmSettings() { return ipmSettings_; }

const vector_t& getInitialState() const { return initialState_; }
const RolloutBase& getRollout() const { return *rolloutPtr_; }
Expand All @@ -93,8 +97,9 @@ class LeggedRobotInterface final : public RobotInterface {
matrix_t initializeInputCostWeight(const std::string& taskFile, const CentroidalModelInfo& info);

std::pair<scalar_t, RelaxedBarrierPenalty::Config> loadFrictionConeSettings(const std::string& taskFile, bool verbose) const;
std::unique_ptr<StateInputCost> getFrictionConeConstraint(size_t contactPointIndex, scalar_t frictionCoefficient,
const RelaxedBarrierPenalty::Config& barrierPenaltyConfig);
std::unique_ptr<StateInputConstraint> getFrictionConeConstraint(size_t contactPointIndex, scalar_t frictionCoefficient);
std::unique_ptr<StateInputCost> getFrictionConeSoftConstraint(size_t contactPointIndex, scalar_t frictionCoefficient,
const RelaxedBarrierPenalty::Config& barrierPenaltyConfig);
std::unique_ptr<StateInputConstraint> getZeroForceConstraint(size_t contactPointIndex);
std::unique_ptr<StateInputConstraint> getZeroVelocityConstraint(const EndEffectorKinematics<scalar_t>& eeKinematics,
size_t contactPointIndex, bool useAnalyticalGradients);
Expand All @@ -105,6 +110,8 @@ class LeggedRobotInterface final : public RobotInterface {
ddp::Settings ddpSettings_;
mpc::Settings mpcSettings_;
sqp::Settings sqpSettings_;
ipm::Settings ipmSettings_;
const bool useHardFrictionConeConstraint_;

std::unique_ptr<PinocchioInterface> pinocchioInterfacePtr_;
CentroidalModelInfo centroidalModelInfo_;
Expand Down
1 change: 1 addition & 0 deletions ocs2_robotic_examples/ocs2_legged_robot/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<depend>ocs2_ddp</depend>
<depend>ocs2_mpc</depend>
<depend>ocs2_sqp</depend>
<depend>ocs2_ipm</depend>
<depend>ocs2_robotic_assets</depend>
<depend>ocs2_robotic_tools</depend>
<depend>ocs2_pinocchio_interface</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,9 @@ namespace legged_robot {
/******************************************************************************************************/
/******************************************************************************************************/
/******************************************************************************************************/
LeggedRobotInterface::LeggedRobotInterface(const std::string& taskFile, const std::string& urdfFile, const std::string& referenceFile) {
LeggedRobotInterface::LeggedRobotInterface(const std::string& taskFile, const std::string& urdfFile, const std::string& referenceFile,
bool useHardFrictionConeConstraint)
: useHardFrictionConeConstraint_(useHardFrictionConeConstraint) {
// check that task file exists
boost::filesystem::path taskFilePath(taskFile);
if (boost::filesystem::exists(taskFilePath)) {
Expand Down Expand Up @@ -92,10 +94,11 @@ LeggedRobotInterface::LeggedRobotInterface(const std::string& taskFile, const st

// load setting from loading file
modelSettings_ = loadModelSettings(taskFile, "model_settings", verbose);
ddpSettings_ = ddp::loadSettings(taskFile, "ddp", verbose);
mpcSettings_ = mpc::loadSettings(taskFile, "mpc", verbose);
rolloutSettings_ = rollout::loadSettings(taskFile, "rollout", verbose);
ddpSettings_ = ddp::loadSettings(taskFile, "ddp", verbose);
sqpSettings_ = sqp::loadSettings(taskFile, "sqp", verbose);
ipmSettings_ = ipm::loadSettings(taskFile, "ipm", verbose);
rolloutSettings_ = rollout::loadSettings(taskFile, "rollout", verbose);

// OptimalConrolProblem
setupOptimalConrolProblem(taskFile, urdfFile, referenceFile, verbose);
Expand Down Expand Up @@ -174,8 +177,12 @@ void LeggedRobotInterface::setupOptimalConrolProblem(const std::string& taskFile
modelSettings_.recompileLibrariesCppAd, modelSettings_.verboseCppAd));
}

problemPtr_->softConstraintPtr->add(footName + "_frictionCone",
getFrictionConeConstraint(i, frictionCoefficient, barrierPenaltyConfig));
if (useHardFrictionConeConstraint_) {
problemPtr_->inequalityConstraintPtr->add(footName + "_frictionCone", getFrictionConeConstraint(i, frictionCoefficient));
} else {
problemPtr_->softConstraintPtr->add(footName + "_frictionCone",
getFrictionConeSoftConstraint(i, frictionCoefficient, barrierPenaltyConfig));
}
problemPtr_->equalityConstraintPtr->add(footName + "_zeroForce", getZeroForceConstraint(i));
problemPtr_->equalityConstraintPtr->add(footName + "_zeroVelocity",
getZeroVelocityConstraint(*eeKinematicsPtr, i, useAnalyticalGradientsConstraints));
Expand Down Expand Up @@ -310,15 +317,20 @@ std::pair<scalar_t, RelaxedBarrierPenalty::Config> LeggedRobotInterface::loadFri
/******************************************************************************************************/
/******************************************************************************************************/
/******************************************************************************************************/
std::unique_ptr<StateInputCost> LeggedRobotInterface::getFrictionConeConstraint(size_t contactPointIndex, scalar_t frictionCoefficient,
const RelaxedBarrierPenalty::Config& barrierPenaltyConfig) {
std::unique_ptr<StateInputConstraint> LeggedRobotInterface::getFrictionConeConstraint(size_t contactPointIndex,
scalar_t frictionCoefficient) {
FrictionConeConstraint::Config frictionConeConConfig(frictionCoefficient);
auto frictionConeConstraintPtr = std::make_unique<FrictionConeConstraint>(*referenceManagerPtr_, std::move(frictionConeConConfig),
contactPointIndex, centroidalModelInfo_);

auto penalty = std::make_unique<RelaxedBarrierPenalty>(barrierPenaltyConfig);
return std::make_unique<FrictionConeConstraint>(*referenceManagerPtr_, std::move(frictionConeConConfig), contactPointIndex,
centroidalModelInfo_);
}

return std::make_unique<StateInputSoftConstraint>(std::move(frictionConeConstraintPtr), std::move(penalty));
/******************************************************************************************************/
/******************************************************************************************************/
/******************************************************************************************************/
std::unique_ptr<StateInputCost> LeggedRobotInterface::getFrictionConeSoftConstraint(
size_t contactPointIndex, scalar_t frictionCoefficient, const RelaxedBarrierPenalty::Config& barrierPenaltyConfig) {
return std::make_unique<StateInputSoftConstraint>(getFrictionConeConstraint(contactPointIndex, frictionCoefficient),
std::make_unique<RelaxedBarrierPenalty>(barrierPenaltyConfig));
}

/******************************************************************************************************/
Expand Down
18 changes: 18 additions & 0 deletions ocs2_robotic_examples/ocs2_legged_robot_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ set(CATKIN_PACKAGE_DEPENDENCIES
ocs2_ddp
ocs2_mpc
ocs2_sqp
ocs2_ipm
ocs2_robotic_tools
ocs2_pinocchio_interface
ocs2_centroidal_model
Expand Down Expand Up @@ -118,6 +119,21 @@ target_link_libraries(legged_robot_sqp_mpc
)
target_compile_options(legged_robot_sqp_mpc PRIVATE ${OCS2_CXX_FLAGS})

## IPM-MPC node for legged robot
add_executable(legged_robot_ipm_mpc
src/LeggedRobotIpmMpcNode.cpp
)
add_dependencies(legged_robot_ipm_mpc
${PROJECT_NAME}
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)
target_link_libraries(legged_robot_ipm_mpc
${PROJECT_NAME}
${catkin_LIBRARIES}
)
target_compile_options(legged_robot_ipm_mpc PRIVATE ${OCS2_CXX_FLAGS})

# Dummy node
add_executable(legged_robot_dummy
src/LeggedRobotDummyNode.cpp
Expand Down Expand Up @@ -174,6 +190,7 @@ if(cmake_clang_tools_FOUND)
${PROJECT_NAME}
legged_robot_ddp_mpc
legged_robot_sqp_mpc
legged_robot_ipm_mpc
legged_robot_dummy
legged_robot_target
legged_robot_gait_command
Expand All @@ -198,6 +215,7 @@ install(
TARGETS
legged_robot_ddp_mpc
legged_robot_sqp_mpc
legged_robot_ipm_mpc
legged_robot_dummy
legged_robot_target
legged_robot_gait_command
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
<?xml version="1.0" ?>

<launch>
<!-- visualization config -->
<arg name="rviz" default="true" />
<arg name="description_name" default="legged_robot_description"/>
<arg name="multiplot" default="false"/>

<!-- The task file for the mpc. -->
<arg name="taskFile" default="$(find ocs2_legged_robot)/config/mpc/task.info"/>
<!-- The reference related config file of the robot -->
<arg name="referenceFile" default="$(find ocs2_legged_robot)/config/command/reference.info"/>
<!-- The URDF model of the robot -->
<arg name="urdfFile" default="$(find ocs2_robotic_assets)/resources/anymal_c/urdf/anymal.urdf"/>
<!-- The file defining gait definition -->
<arg name="gaitCommandFile" default="$(find ocs2_legged_robot)/config/command/gait.info"/>

<!-- rviz -->
<group if="$(arg rviz)">
<param name="$(arg description_name)" textfile="$(arg urdfFile)"/>
<arg name="rvizconfig" default="$(find ocs2_legged_robot_ros)/rviz/legged_robot.rviz" />
<node pkg="rviz" type="rviz" name="rviz" args="-d $(arg rvizconfig)" output="screen" />
</group>

<!-- multiplot -->
<group if="$(arg multiplot)">
<include file="$(find ocs2_legged_robot_ros)/launch/multiplot.launch">
<arg name="metrics_config" value="$(find ocs2_legged_robot)/config/multiplot/friction_cone.xml" />
</include>
</group>

<!-- make the files into global parameters -->
<param name="multiplot" value="$(arg multiplot)"/>
<param name="taskFile" value="$(arg taskFile)" />
<param name="referenceFile" value="$(arg referenceFile)" />
<param name="urdfFile" value="$(arg urdfFile)" />
<param name="gaitCommandFile" value="$(arg gaitCommandFile)"/>

<node pkg="ocs2_legged_robot_ros" type="legged_robot_ipm_mpc" name="legged_robot_ipm_mpc"
output="screen" launch-prefix=""/>

<node pkg="ocs2_legged_robot_ros" type="legged_robot_dummy" name="legged_robot_dummy"
output="screen" launch-prefix="gnome-terminal --"/>

<node pkg="ocs2_legged_robot_ros" type="legged_robot_target" name="legged_robot_target"
output="screen" launch-prefix="gnome-terminal --"/>

<node pkg="ocs2_legged_robot_ros" type="legged_robot_gait_command" name="legged_robot_gait_command"
output="screen" launch-prefix="gnome-terminal --"/>
</launch>
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0" ?>

<launch>
<arg name="metrics_config" default="$(find ocs2_legged_robot)/config/multiplot/mpc_metrics.xml" />
<arg name="metrics_config" default="$(find ocs2_legged_robot)/config/multiplot/zero_velocity.xml" />

<node name="mpc_metrics" pkg="rqt_multiplot" type="rqt_multiplot"
args="--multiplot-run-all --multiplot-config $(arg metrics_config)"
Expand Down
1 change: 1 addition & 0 deletions ocs2_robotic_examples/ocs2_legged_robot_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<depend>ocs2_ddp</depend>
<depend>ocs2_mpc</depend>
<depend>ocs2_sqp</depend>
<depend>ocs2_ipm</depend>
<depend>ocs2_robotic_tools</depend>
<depend>ocs2_pinocchio_interface</depend>
<depend>ocs2_centroidal_model</depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,96 @@
/******************************************************************************
Copyright (c) 2017, Farbod Farshidian. All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
******************************************************************************/

#include <ros/init.h>
#include <ros/package.h>

#include <ocs2_ipm/IpmMpc.h>
#include <ocs2_legged_robot/LeggedRobotInterface.h>
#include <ocs2_ros_interfaces/mpc/MPC_ROS_Interface.h>
#include <ocs2_ros_interfaces/synchronized_module/RosReferenceManager.h>
#include <ocs2_ros_interfaces/synchronized_module/SolverObserverRosCallbacks.h>

#include "ocs2_legged_robot_ros/gait/GaitReceiver.h"

using namespace ocs2;
using namespace legged_robot;

int main(int argc, char** argv) {
const std::string robotName = "legged_robot";

// Initialize ros node
::ros::init(argc, argv, robotName + "_mpc");
::ros::NodeHandle nodeHandle;
// Get node parameters
bool multiplot = false;
std::string taskFile, urdfFile, referenceFile;
nodeHandle.getParam("/multiplot", multiplot);
nodeHandle.getParam("/taskFile", taskFile);
nodeHandle.getParam("/urdfFile", urdfFile);
nodeHandle.getParam("/referenceFile", referenceFile);

// Robot interface
constexpr bool useHardFrictionConeConstraint = true;
LeggedRobotInterface interface(taskFile, urdfFile, referenceFile, useHardFrictionConeConstraint);

// Gait receiver
auto gaitReceiverPtr =
std::make_shared<GaitReceiver>(nodeHandle, interface.getSwitchedModelReferenceManagerPtr()->getGaitSchedule(), robotName);

// ROS ReferenceManager
auto rosReferenceManagerPtr = std::make_shared<RosReferenceManager>(robotName, interface.getReferenceManagerPtr());
rosReferenceManagerPtr->subscribe(nodeHandle);

// MPC
IpmMpc mpc(interface.mpcSettings(), interface.ipmSettings(), interface.getOptimalControlProblem(), interface.getInitializer());
mpc.getSolverPtr()->setReferenceManager(rosReferenceManagerPtr);
mpc.getSolverPtr()->addSynchronizedModule(gaitReceiverPtr);

// observer for friction cone constraints (only add this for debugging as it slows down the solver)
if (multiplot) {
auto createStateInputBoundsObserver = [&](const std::string& termName) {
const ocs2::scalar_array_t observingTimePoints{0.0};
const std::vector<std::string> topicNames{"metrics/" + termName + "/0MsLookAhead"};
auto callback = ocs2::ros::createConstraintCallback(nodeHandle, {0.0}, topicNames,
ocs2::ros::CallbackInterpolationStrategy::linear_interpolation);
return ocs2::SolverObserver::ConstraintTermObserver(ocs2::SolverObserver::Type::Intermediate, termName, std::move(callback));
};
for (size_t i = 0; i < interface.getCentroidalModelInfo().numThreeDofContacts; i++) {
const std::string& footName = interface.modelSettings().contactNames3DoF[i];
mpc.getSolverPtr()->addSolverObserver(createStateInputBoundsObserver(footName + "_frictionCone"));
}
}

// Launch MPC ROS node
MPC_ROS_Interface mpcNode(mpc, robotName);
mpcNode.launchNodes(nodeHandle);

// Successful exit
return 0;
}

0 comments on commit 3fba74e

Please sign in to comment.