Skip to content

Commit

Permalink
Adapt to recent changes in wbc_lib
Browse files Browse the repository at this point in the history
  • Loading branch information
dmronga committed Feb 23, 2024
1 parent 3e7f5a2 commit a209ece
Show file tree
Hide file tree
Showing 18 changed files with 33 additions and 33 deletions.
22 changes: 11 additions & 11 deletions ctrl_lib.orogen
Original file line number Diff line number Diff line change
Expand Up @@ -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<std/string>")

# 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")
Expand Down Expand Up @@ -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
Expand All @@ -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<ctrl_lib/PotentialFieldInfo>")
output_port("field_infos", "std/vector<wbc/PotentialFieldInfo>")
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
Expand All @@ -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<ctrl_lib/PotentialFieldInfo>")
output_port("field_infos", "std/vector<wbc/PotentialFieldInfo>")
output_port("euclidean_distance", "base/VectorXd")

periodic 0.001
Expand All @@ -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.
Expand All @@ -280,7 +280,7 @@ task_context "JointTorqueController", subclasses: "ControllerTask" do
end

typekit do
export_types "ctrl_lib/ActivationFunction"
export_types "std/vector<ctrl_lib/PotentialFieldInfo>"
export_types "ctrl_lib/PotentialFieldInfo"
export_types "wbc/ActivationFunction"
export_types "std/vector<wbc/PotentialFieldInfo>"
export_types "wbc/PotentialFieldInfo"
end
2 changes: 1 addition & 1 deletion tasks/CartesianForceController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
4 changes: 2 additions & 2 deletions tasks/CartesianForceController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;

};
}
Expand Down
2 changes: 1 addition & 1 deletion tasks/CartesianPositionController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
2 changes: 1 addition & 1 deletion tasks/CartesianPositionController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
};
}

Expand Down
2 changes: 1 addition & 1 deletion tasks/CartesianRadialPotentialFields.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
6 changes: 3 additions & 3 deletions tasks/CartesianRadialPotentialFields.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -40,7 +40,7 @@ class CartesianRadialPotentialFields : public CartesianRadialPotentialFieldsBase
double influence_distance;
base::samples::RigidBodyStateSE3 control_output, feedback;
std::vector<base::samples::RigidBodyState> pot_field_centers;
PotentialFieldsController* controller;
wbc::PotentialFieldsController* controller;
std::vector<PotentialFieldInfo> field_infos;
};
}
Expand Down
2 changes: 1 addition & 1 deletion tasks/JointLimitAvoidance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());

Expand Down
4 changes: 2 additions & 2 deletions tasks/JointLimitAvoidance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
};
}

Expand Down
2 changes: 1 addition & 1 deletion tasks/JointPositionController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
4 changes: 2 additions & 2 deletions tasks/JointPositionController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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;
};
}

Expand Down
2 changes: 1 addition & 1 deletion tasks/JointTorqueController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
2 changes: 1 addition & 1 deletion tasks/JointTorqueController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

};
}
Expand Down
2 changes: 1 addition & 1 deletion test/config/ctrl_lib::CartesianForceController.yml
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 1 addition & 1 deletion test/config/ctrl_lib::CartesianPositionController.yml
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 1 addition & 1 deletion test/config/ctrl_lib::CartesianRadialPotentialFields.yml
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 1 addition & 1 deletion test/config/ctrl_lib::JointLimitAvoidance.yml
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 1 addition & 1 deletion test/config/ctrl_lib::JointPositionController.yml
Original file line number Diff line number Diff line change
@@ -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
Expand Down

0 comments on commit a209ece

Please sign in to comment.