Skip to content

Commit

Permalink
Remove ctrl_lib namespace and replace with wbc for better code consis…
Browse files Browse the repository at this point in the history
…tency
  • Loading branch information
dmronga committed Feb 23, 2024
1 parent da45951 commit 9b26222
Show file tree
Hide file tree
Showing 38 changed files with 41 additions and 43 deletions.
2 changes: 1 addition & 1 deletion src/controllers/ActivationFunction.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <base/Eigen.hpp>
#include <stdexcept>

namespace ctrl_lib{
namespace wbc{

enum activationType{NO_ACTIVATION, /** Activation values will always be one */
STEP_ACTIVATION, /** If input > threshold, activation will be one, else 0 */
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/CartesianForcePIDController.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "CartesianForcePIDController.hpp"

namespace ctrl_lib {
namespace wbc {

CartesianForcePIDController::CartesianForcePIDController() :
PIDController(6){
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/CartesianForcePIDController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include <base/samples/Wrench.hpp>
#include <base/samples/RigidBodyStateSE3.hpp>

namespace ctrl_lib {
namespace wbc {

/**
* @brief CartesianForcePIDController implements a PID Controller on a Wrench data type
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/CartesianPosPDController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#include "ControllerTools.hpp"
#include <base/samples/RigidBodyStateSE3.hpp>

namespace ctrl_lib{
namespace wbc{

CartesianPosPDController::CartesianPosPDController() :
PosPDController(6){
Expand Down
6 changes: 3 additions & 3 deletions src/controllers/CartesianPosPDController.hpp
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
#ifndef CTRL_LIB_CART_POS_PD_CONTROLLER_HPP
#define CTRL_LIB_CART_POS_PD_CONTROLLER_HPP
#ifndef WBC_CART_POS_PD_CONTROLLER_HPP
#define WBC_CART_POS_PD_CONTROLLER_HPP

#include "PosPDController.hpp"
#include <base/samples/RigidBodyStateSE3.hpp>

namespace ctrl_lib {
namespace wbc {

/**
* @brief The CartesianPosPDController class implements a PD Controller with feed forward on the RigidBodyStateSE3 type. The following control schemes are available:
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/CartesianPotentialFieldsController.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include "CartesianPotentialFieldsController.hpp"
#include <stdexcept>

using namespace ctrl_lib;
using namespace wbc;

CartesianPotentialFieldsController::CartesianPotentialFieldsController() :
PotentialFieldsController(3){
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/CartesianPotentialFieldsController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include "PotentialFieldsController.hpp"
#include <base/samples/RigidBodyStateSE3.hpp>

namespace ctrl_lib{
namespace wbc{

/**
* @brief The PotentialFieldsController class implements a multi potential field controller in Cartesian space.
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/JointLimitAvoidanceController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

using namespace std;

namespace ctrl_lib {
namespace wbc {

JointLimitAvoidanceController::JointLimitAvoidanceController(const base::JointLimits& limits,
const base::VectorXd &influence_distance) :
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/JointLimitAvoidanceController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <base/JointLimits.hpp>
#include <base/commands/Joints.hpp>

namespace ctrl_lib {
namespace wbc {

class JointLimitAvoidanceController : public PotentialFieldsController{
protected:
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/JointPosPDController.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "JointPosPDController.hpp"

namespace ctrl_lib{
namespace wbc{

JointPosPDController::JointPosPDController(const std::vector<std::string>& joint_names) :
PosPDController(joint_names.size()),
Expand Down
6 changes: 3 additions & 3 deletions src/controllers/JointPosPDController.hpp
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
#ifndef CTRL_LIB_JOINT_POS_PD_CONTROLLER_HPP
#define CTRL_LIB_JOINT_POS_PD_CONTROLLER_HPP
#ifndef WBC_JOINT_POS_PD_CONTROLLER_HPP
#define WBC_JOINT_POS_PD_CONTROLLER_HPP

#include "PosPDController.hpp"
#include <base/commands/Joints.hpp>

namespace ctrl_lib {
namespace wbc {

/**
* @brief The JointPosPDController class implements a PD Controller with feed forward on the base-Joints type. The following control schemes are available:
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/JointTorquePIDController.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "JointTorquePIDController.hpp"

namespace ctrl_lib{
namespace wbc{

JointTorquePIDController::JointTorquePIDController(const std::vector<std::string>& joint_names) :
PIDController(joint_names.size()),
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/JointTorquePIDController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include "PIDController.hpp"
#include <base/commands/Joints.hpp>

namespace ctrl_lib{
namespace wbc{

class JointTorquePIDController : public PIDController{
protected:
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PIDController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

using namespace std;

namespace ctrl_lib{
namespace wbc{

PIDController::PIDController(uint dimension) :
dimension(dimension){
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PIDController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <base/Eigen.hpp>
#include "PIDCtrlParams.hpp"

namespace ctrl_lib{
namespace wbc{

/**
* @brief The PIDController class implements an n-dimensional PID controller
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PIDCtrlParams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

#include <base/Eigen.hpp>

namespace ctrl_lib{
namespace wbc{

class PIDCtrlParams{
public:
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PlanarPotentialField.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "PlanarPotentialField.hpp"

using namespace ctrl_lib;
using namespace wbc;

PlanarPotentialField::PlanarPotentialField(const std::string &_name)
: PotentialField(3, _name){
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PlanarPotentialField.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include "PotentialField.hpp"

namespace ctrl_lib{
namespace wbc{

class PotentialField;

Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PosPDController.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "PosPDController.hpp"

namespace ctrl_lib {
namespace wbc {

PosPDController::PosPDController(size_t dim_controller) :
dim_controller(dim_controller){
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PosPDController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

#include <base/Eigen.hpp>

namespace ctrl_lib {
namespace wbc {

/**
* @brief The PosPDController class implements the following two control scemes
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PotentialField.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include <stdexcept>
#include <memory>

namespace ctrl_lib{
namespace wbc{

/**
* @brief Base class for potential fields
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PotentialFieldInfo.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

#include "PotentialField.hpp"

namespace ctrl_lib {
namespace wbc {

struct PotentialFieldInfo{

Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PotentialFieldsController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#include <stdexcept>
#include <limits>

using namespace ctrl_lib;
using namespace wbc;
using namespace std;

PotentialFieldsController::PotentialFieldsController(const uint _dimension)
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/PotentialFieldsController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include "PotentialFieldInfo.hpp"
#include <vector>

namespace ctrl_lib{
namespace wbc{

/**
* @brief Base class for potential field controllers
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/RadialPotentialField.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "RadialPotentialField.hpp"

using namespace ctrl_lib;
using namespace wbc;

RadialPotentialField::RadialPotentialField(const uint _dimension, const std::string& _name)
: PotentialField(_dimension, _name){
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/RadialPotentialField.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include "PotentialField.hpp"

namespace ctrl_lib{
namespace wbc{

/**
* @brief Radial Potential field. The computed gradient will be constant on volumnes with
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/test/test_pid_controllers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include <base/samples//RigidBodyStateSE3.hpp>

using namespace std;
using namespace ctrl_lib;
using namespace wbc;


BOOST_AUTO_TEST_CASE(configuration_test){
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/test/test_pos_pd_controllers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include <base/samples/RigidBodyStateSE3.hpp>

using namespace std;
using namespace ctrl_lib;
using namespace wbc;


BOOST_AUTO_TEST_CASE(configuration_test){
Expand Down
2 changes: 1 addition & 1 deletion src/controllers/test/test_pot_field_controllers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include "../JointLimitAvoidanceController.hpp"

using namespace std;
using namespace ctrl_lib;
using namespace wbc;

void runPotentialFieldController(std::string filename,
CartesianPotentialFieldsController* ctrl,
Expand Down
2 changes: 1 addition & 1 deletion tutorials/kuka_iiwa/cart_pos_ctrl_hls.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ int main(){
// v_d = kd*v_r + kp(x_r - x).
//
// As we don't use feed forward velocity here, we can ignore the factor kd.
ctrl_lib::CartesianPosPDController controller;
CartesianPosPDController controller;
controller.setPGain(base::Vector6d::Constant(1)); // Set kp

// Choose an initial joint state. For velocity-based WBC only the current position of all joint has to be passed
Expand Down
4 changes: 2 additions & 2 deletions tutorials/kuka_iiwa/cart_pos_ctrl_hls_hierarchies.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,9 +63,9 @@ int main(int argc, char** argv){
return -1;

// Configure the controllers, one Cartesian position controller, one joint Position controller
ctrl_lib::CartesianPosPDController cart_controller;
CartesianPosPDController cart_controller;
cart_controller.setPGain(base::Vector6d::Constant(1)); // Set kp
ctrl_lib::JointPosPDController jnt_controller(jnt_task.joint_names);
JointPosPDController jnt_controller(jnt_task.joint_names);
base::VectorXd p_gain(1);
p_gain.setConstant(1);
jnt_controller.setPGain(p_gain);
Expand Down
2 changes: 1 addition & 1 deletion tutorials/kuka_iiwa/cart_pos_ctrl_hls_weights.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ int main(){
// v_d = kd*v_r + kp(x_r - x).
//
// As we don't use feed forward velocity here, we can ignore the factor kd.
ctrl_lib::CartesianPosPDController controller;
CartesianPosPDController controller;
controller.setPGain(base::Vector6d::Constant(1)); // Set kp

// Choose an initial joint state. For velocity-based WBC only the current position of all joint has to be passed
Expand Down
2 changes: 1 addition & 1 deletion tutorials/kuka_iiwa/cart_pos_ctrl_qpoases.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ int main(){
// v_d = kd*v_r + kp(x_r - x).
//
// As we don't use feed forward velocity here, we can ignore the factor kd.
ctrl_lib::CartesianPosPDController controller;
CartesianPosPDController controller;
controller.setPGain(base::Vector6d::Constant(1));

// Choose an initial joint state. For velocity-based WBC only the current position of all joint has to be passed
Expand Down
2 changes: 1 addition & 1 deletion tutorials/rh5/rh5_legs_floating_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
using namespace wbc;
using namespace std;
using namespace qpOASES;
using namespace ctrl_lib;
using namespace wbc;

/**
* Velocity-based example, Cartesian position control on two 6 dof legs of the RH5 humanoid including floating base and two contact points (feet).
Expand Down
2 changes: 1 addition & 1 deletion tutorials/rh5/rh5_single_leg.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
using namespace wbc;
using namespace std;
using namespace qpOASES;
using namespace ctrl_lib;
using namespace wbc;

/**
* Velocity-based example, Cartesian position control on 6 dof leg of the RH5 humanoid (fixed base/fully actuated, serial robot model). In the example the following problem is solved:
Expand Down
1 change: 0 additions & 1 deletion tutorials/rh5/rh5_single_leg_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
using namespace wbc;
using namespace std;
using namespace qpOASES;
using namespace ctrl_lib;

/**
* Velocity-based example, exact same problem as in the rh5_single_leg example. The only difference is that here we use the hybrid robot model, i.e. we
Expand Down
2 changes: 1 addition & 1 deletion tutorials/rh5v2/rh5v2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

using namespace std;
using namespace wbc;
using namespace ctrl_lib;
using namespace wbc;

/**
* Acceleration-based example, Cartesian position control of the RH5v2 arms (fixed base, no contacts).
Expand Down
1 change: 0 additions & 1 deletion tutorials/rh5v2/rh5v2_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@

using namespace std;
using namespace wbc;
using namespace ctrl_lib;

/**
* Acceleration-based example, same problem as in the rh5v2 example. The only difference is that here we use the hybrid robot model, i.e. we
Expand Down

0 comments on commit 9b26222

Please sign in to comment.