diff --git a/ctrl_lib.orogen b/ctrl_lib.orogen index 3501999..6404683 100644 --- a/ctrl_lib.orogen +++ b/ctrl_lib.orogen @@ -30,8 +30,8 @@ task_context "ControllerTask" do # Unique name for each variable, e.g. joint names in case of a joint space controller. property("field_names", "std/vector") - # Type of activation function used. See ctrl_lib/ActivationFunction.hpp for details. - property("activation_function", "ctrl_lib/ActivationFunction") + # Type of activation function used. See wbc/controllers/ActivationFunction.hpp for details. + property("activation_function", "wbc/ActivationFunction") # Current activation values output_port("activation", "base/VectorXd") @@ -179,7 +179,7 @@ end # # Implementation of RadialPotentialFields in joint space. Each joint will have one 1-dimensional potential field. -# See ctrl_lib/RadialPotentialField.hpp and ctrl_lib/JointPotentialFieldsController.hpp for details +# See wbc/controllers/RadialPotentialField.hpp and wbc/controllers/JointPotentialFieldsController.hpp for details # task_context "JointLimitAvoidance", subclasses: "ControllerTask" do needs_configuration @@ -206,15 +206,15 @@ task_context "JointLimitAvoidance", subclasses: "ControllerTask" do # Debug ports output_port("current_feedback", "base/samples/Joints") - output_port("field_infos", "std/vector") + output_port("field_infos", "std/vector") output_port("current_joint_limits", "base/JointLimits") periodic 0.001 end # -# Implementation of RadialPotentialFields in Cartesian space. Dimension of all fields has to be 3! See ctrl_lib/RadialPotentialField.hpp and -# ctrl_lib/PotentialFieldsController.hpp for details +# Implementation of RadialPotentialFields in Cartesian space. Dimension of all fields has to be 3! See wbc/controllers/RadialPotentialField.hpp +# and wbc/controllers/PotentialFieldsController.hpp for details # task_context "CartesianRadialPotentialFields", subclasses: "ControllerTask" do needs_configuration @@ -240,7 +240,7 @@ task_context "CartesianRadialPotentialFields", subclasses: "ControllerTask" do # Debug ports: output_port("current_feedback", "base/samples/RigidBodyStateSE3") - output_port("field_infos", "std/vector") + output_port("field_infos", "std/vector") output_port("euclidean_distance", "base/VectorXd") periodic 0.001 @@ -253,7 +253,7 @@ task_context "JointTorqueController", subclasses: "ControllerTask" do needs_configuration # PID gains. Size has to be the same as size of field_names. - property("pid_params", "ctrl_lib/PIDCtrlParams") + property("pid_params", "wbc/PIDCtrlParams") # Maximum control output (saturation). If one output value exceeds maximum, all # other values will be scaled accordingly. Size has to be the same as size of field_names. @@ -280,7 +280,7 @@ task_context "JointTorqueController", subclasses: "ControllerTask" do end typekit do - export_types "ctrl_lib/ActivationFunction" - export_types "std/vector" - export_types "ctrl_lib/PotentialFieldInfo" + export_types "wbc/ActivationFunction" + export_types "std/vector" + export_types "wbc/PotentialFieldInfo" end diff --git a/tasks/CartesianForceController.cpp b/tasks/CartesianForceController.cpp index 4d2f6a8..05687fe 100644 --- a/tasks/CartesianForceController.cpp +++ b/tasks/CartesianForceController.cpp @@ -18,7 +18,7 @@ bool CartesianForceController::configureHook(){ if (! CartesianForceControllerBase::configureHook()) return false; - controller = new CartesianForcePIDController(); + controller = new wbc::CartesianForcePIDController(); PIDCtrlParams params(controller->getDimension()); params.p_gain = _p_gain.get(); params.i_gain.setZero(); diff --git a/tasks/CartesianForceController.hpp b/tasks/CartesianForceController.hpp index 082c85c..8b7cb27 100644 --- a/tasks/CartesianForceController.hpp +++ b/tasks/CartesianForceController.hpp @@ -12,7 +12,7 @@ namespace ctrl_lib{ class CartesianForcePIDController; -/*! \class CartesianForceController Implementation of a force controller in Cartesian space. See ctrl_lib/ProportionalController.hpp for details*/ +/*! \class CartesianForceController Implementation of a force controller in Cartesian space. See wbc/controllers/ProportionalController.hpp for details*/ class CartesianForceController : public CartesianForceControllerBase { friend class CartesianForceControllerBase; @@ -56,7 +56,7 @@ class CartesianForceController : public CartesianForceControllerBase std::string ft_sensor_name; base::VectorXd setpoint_raw, feedback_raw, ctrl_output_raw; base::samples::RigidBodyStateSE3 control_output; - CartesianForcePIDController* controller; + wbc::CartesianForcePIDController* controller; }; } diff --git a/tasks/CartesianPositionController.cpp b/tasks/CartesianPositionController.cpp index 1f81efb..73f69fc 100644 --- a/tasks/CartesianPositionController.cpp +++ b/tasks/CartesianPositionController.cpp @@ -18,7 +18,7 @@ bool CartesianPositionController::configureHook(){ if (! CartesianPositionControllerBase::configureHook()) return false; - controller = new CartesianPosPDController(); + controller = new wbc::CartesianPosPDController(); controller->setPGain(_p_gain.get()); controller->setDGain(_d_gain.get()); controller->setFFGain(_ff_gain.get()); diff --git a/tasks/CartesianPositionController.hpp b/tasks/CartesianPositionController.hpp index 4c414e5..ba4c31f 100644 --- a/tasks/CartesianPositionController.hpp +++ b/tasks/CartesianPositionController.hpp @@ -37,7 +37,7 @@ class CartesianPositionController : public CartesianPositionControllerBase virtual const base::VectorXd& computeActivation(ActivationFunction& activation_function); base::samples::RigidBodyStateSE3 setpoint, control_output, feedback; - CartesianPosPDController* controller; + wbc::CartesianPosPDController* controller; }; } diff --git a/tasks/CartesianRadialPotentialFields.cpp b/tasks/CartesianRadialPotentialFields.cpp index 7a9b571..630b29d 100644 --- a/tasks/CartesianRadialPotentialFields.cpp +++ b/tasks/CartesianRadialPotentialFields.cpp @@ -19,7 +19,7 @@ bool CartesianRadialPotentialFields::configureHook(){ if(!CartesianRadialPotentialFieldsBase::configureHook()) return false; - controller = new CartesianPotentialFieldsController(); + controller = new wbc::CartesianPotentialFieldsController(); controller->setPGain(_p_gain.get()); controller->setMaxControlOutput(_max_control_output.get()); influence_distance = _influence_distance.get(); diff --git a/tasks/CartesianRadialPotentialFields.hpp b/tasks/CartesianRadialPotentialFields.hpp index 0acf53d..6109736 100644 --- a/tasks/CartesianRadialPotentialFields.hpp +++ b/tasks/CartesianRadialPotentialFields.hpp @@ -10,8 +10,8 @@ namespace ctrl_lib { class PotentialFieldsController; -/*! \class CartesianRadialPotentialFields Implementation of RadialPotentialFields in Cartesian space. Dimension of all fields has to be 3! See ctrl_lib/RadialPotentialField.hpp and -ctrl_lib/PotentialFieldsController.hpp for details */ +/*! \class CartesianRadialPotentialFields Implementation of RadialPotentialFields in Cartesian space. Dimension of all fields has to be 3! See wbc/controllers/RadialPotentialField.hpp and +wbc/controllers/PotentialFieldsController.hpp for details */ class CartesianRadialPotentialFields : public CartesianRadialPotentialFieldsBase { friend class CartesianRadialPotentialFieldsBase; @@ -40,7 +40,7 @@ class CartesianRadialPotentialFields : public CartesianRadialPotentialFieldsBase double influence_distance; base::samples::RigidBodyStateSE3 control_output, feedback; std::vector pot_field_centers; - PotentialFieldsController* controller; + wbc::PotentialFieldsController* controller; std::vector field_infos; }; } diff --git a/tasks/JointLimitAvoidance.cpp b/tasks/JointLimitAvoidance.cpp index 4b74f13..d5372f5 100644 --- a/tasks/JointLimitAvoidance.cpp +++ b/tasks/JointLimitAvoidance.cpp @@ -22,7 +22,7 @@ bool JointLimitAvoidance::configureHook(){ joint_limits = _joint_limits.get(); joint_limits.names = field_names; - controller = new JointLimitAvoidanceController(joint_limits, _influence_distance.get()); + controller = new wbc::JointLimitAvoidanceController(joint_limits, _influence_distance.get()); controller->setPGain(_p_gain.get()); controller->setMaxControlOutput(_max_control_output.get()); diff --git a/tasks/JointLimitAvoidance.hpp b/tasks/JointLimitAvoidance.hpp index 26c6718..1cfa51e 100644 --- a/tasks/JointLimitAvoidance.hpp +++ b/tasks/JointLimitAvoidance.hpp @@ -11,7 +11,7 @@ namespace ctrl_lib{ class JointLimitAvoidanceController; /*! \class JointLimitAvoidance Implementation of RadialPotentialFields in joint space. Each joint will have one 1-dimensional potential field. -See ctrl_lib/RadialPotentialField.hpp and ctrl_lib/PotentialFieldsController.hpp for details */ +See wbc/controllers/RadialPotentialField.hpp and wbc/controllers/PotentialFieldsController.hpp for details */ class JointLimitAvoidance : public JointLimitAvoidanceBase { friend class JointLimitAvoidanceBase; @@ -42,7 +42,7 @@ class JointLimitAvoidance : public JointLimitAvoidanceBase base::VectorXd position_raw; base::commands::Joints control_output; base::VectorXd influence_distance; - JointLimitAvoidanceController* controller; + wbc::JointLimitAvoidanceController* controller; }; } diff --git a/tasks/JointPositionController.cpp b/tasks/JointPositionController.cpp index 9862a2a..bf063c2 100644 --- a/tasks/JointPositionController.cpp +++ b/tasks/JointPositionController.cpp @@ -18,7 +18,7 @@ bool JointPositionController::configureHook(){ if (! JointPositionControllerBase::configureHook()) return false; - controller = new JointPosPDController(_field_names.get()); + controller = new wbc::JointPosPDController(_field_names.get()); controller->setPGain(_p_gain.get()); controller->setDGain(_d_gain.get()); controller->setFFGain(_ff_gain.get()); diff --git a/tasks/JointPositionController.hpp b/tasks/JointPositionController.hpp index 4388ab0..a371f7b 100644 --- a/tasks/JointPositionController.hpp +++ b/tasks/JointPositionController.hpp @@ -10,7 +10,7 @@ namespace ctrl_lib { class JointPosPDController; -/*! \class JointPositionController Implementation of PositionControlFeedForward in joint space. See ctrl_lib/PositionControlFeedForward.hpp for details*/ +/*! \class JointPositionController Implementation of PositionControlFeedForward in joint space. See wbc/controllers/PositionControlFeedForward.hpp for details*/ class JointPositionController : public JointPositionControllerBase { friend class JointPositionControllerBase; @@ -37,7 +37,7 @@ class JointPositionController : public JointPositionControllerBase virtual const base::VectorXd& computeActivation(ActivationFunction& activation_function); base::commands::Joints setpoint, control_output, feedback; - JointPosPDController* controller; + wbc::JointPosPDController* controller; }; } diff --git a/tasks/JointTorqueController.cpp b/tasks/JointTorqueController.cpp index 0f7e31a..b9ae60e 100644 --- a/tasks/JointTorqueController.cpp +++ b/tasks/JointTorqueController.cpp @@ -18,7 +18,7 @@ bool JointTorqueController::configureHook(){ if (! JointTorqueControllerBase::configureHook()) return false; - controller = new JointTorquePIDController(_field_names.get()); + controller = new wbc::JointTorquePIDController(_field_names.get()); controller->setPID(_pid_params.get()); controller->setMaxCtrlOutput(_max_control_output.get()); controller->setDeadZone(_dead_zone.get()); diff --git a/tasks/JointTorqueController.hpp b/tasks/JointTorqueController.hpp index 6d6aba1..1506db1 100644 --- a/tasks/JointTorqueController.hpp +++ b/tasks/JointTorqueController.hpp @@ -37,7 +37,7 @@ class JointTorqueController : public JointTorqueControllerBase virtual const base::VectorXd& computeActivation(ActivationFunction& activation_function); base::commands::Joints setpoint, control_output, feedback; - JointTorquePIDController* controller; + wbc::JointTorquePIDController* controller; }; } diff --git a/test/config/ctrl_lib::CartesianForceController.yml b/test/config/ctrl_lib::CartesianForceController.yml index 89aacfa..d218f87 100644 --- a/test/config/ctrl_lib::CartesianForceController.yml +++ b/test/config/ctrl_lib::CartesianForceController.yml @@ -1,5 +1,5 @@ --- name:default -# Type of activation function used. See ctrl_lib/ActivationFunction.hpp for details. +# Type of activation function used. See wbc/controllers/ActivationFunction.hpp for details. activation_function: threshold: 0.0 type: :NO_ACTIVATION diff --git a/test/config/ctrl_lib::CartesianPositionController.yml b/test/config/ctrl_lib::CartesianPositionController.yml index a34672f..2a17a38 100644 --- a/test/config/ctrl_lib::CartesianPositionController.yml +++ b/test/config/ctrl_lib::CartesianPositionController.yml @@ -1,5 +1,5 @@ --- name:default -# Type of activation function used. See ctrl_lib/ActivationFunction.hpp for details. +# Type of activation function used. See wbc/controllers/ActivationFunction.hpp for details. activation_function: threshold: 0.0 type: :NO_ACTIVATION diff --git a/test/config/ctrl_lib::CartesianRadialPotentialFields.yml b/test/config/ctrl_lib::CartesianRadialPotentialFields.yml index 49a5263..ca6d0b3 100644 --- a/test/config/ctrl_lib::CartesianRadialPotentialFields.yml +++ b/test/config/ctrl_lib::CartesianRadialPotentialFields.yml @@ -1,5 +1,5 @@ --- name:default -# Type of activation function used. See ctrl_lib/ActivationFunction.hpp for details. +# Type of activation function used. See wbc/controllers/ActivationFunction.hpp for details. activation_function: threshold: 0.0 type: :NO_ACTIVATION diff --git a/test/config/ctrl_lib::JointLimitAvoidance.yml b/test/config/ctrl_lib::JointLimitAvoidance.yml index c7cdbff..8242a24 100644 --- a/test/config/ctrl_lib::JointLimitAvoidance.yml +++ b/test/config/ctrl_lib::JointLimitAvoidance.yml @@ -1,5 +1,5 @@ --- name:default -# Type of activation function used. See ctrl_lib/ActivationFunction.hpp for details. +# Type of activation function used. See wbc/controllers/ActivationFunction.hpp for details. activation_function: threshold: 0.5 type: :LINEAR_ACTIVATION diff --git a/test/config/ctrl_lib::JointPositionController.yml b/test/config/ctrl_lib::JointPositionController.yml index 68241b4..74811b0 100644 --- a/test/config/ctrl_lib::JointPositionController.yml +++ b/test/config/ctrl_lib::JointPositionController.yml @@ -1,5 +1,5 @@ --- name:default -# Type of activation function used. See ctrl_lib/ActivationFunction.hpp for details. +# Type of activation function used. See wbc/controllers/ActivationFunction.hpp for details. activation_function: threshold: 0.0 type: :NO_ACTIVATION