Skip to content

Commit

Permalink
removing the debug logs
Browse files Browse the repository at this point in the history
  • Loading branch information
MaximilienNaveau committed Nov 29, 2024
1 parent 655f7fc commit 1f244eb
Showing 1 changed file with 0 additions and 18 deletions.
18 changes: 0 additions & 18 deletions src/linear_feedback_controller_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,6 @@ LinearFeedbackControllerRos::LinearFeedbackControllerRos()
LinearFeedbackControllerRos::~LinearFeedbackControllerRos() {}

CallbackReturn LinearFeedbackControllerRos::on_init() {
// DEBUG
RCLCPP_WARN(get_node()->get_logger(), "on_init.");
bool all_good = true;
std::string robot_description = "";
if (!load_parameters()) {
Expand Down Expand Up @@ -66,8 +64,6 @@ CallbackReturn LinearFeedbackControllerRos::on_init() {

InterfaceConfiguration
LinearFeedbackControllerRos::command_interface_configuration() const {
// DEBUG
RCLCPP_WARN(get_node()->get_logger(), "command_interface_configuration");
// Output the estimated robot state as command interface.
std::vector<std::string> command_interfaces_config_names = {};

Expand All @@ -91,8 +87,6 @@ LinearFeedbackControllerRos::command_interface_configuration() const {

InterfaceConfiguration
LinearFeedbackControllerRos::state_interface_configuration() const {
// DEBUG
RCLCPP_WARN(get_node()->get_logger(), "state_interface_configuration");
// Get the joint state measurements.
std::vector<std::string> state_interfaces_config_names;

Expand All @@ -118,8 +112,6 @@ LinearFeedbackControllerRos::state_interface_configuration() const {

std::vector<hardware_interface::CommandInterface>
LinearFeedbackControllerRos::on_export_reference_interfaces() {
// DEBUG
RCLCPP_WARN(get_node()->get_logger(), "on_export_reference_interfaces");
std::vector<hardware_interface::CommandInterface> reference_interfaces;
reference_interfaces.clear();
for (size_t i = 0; i < reference_interface_names_.size(); ++i) {
Expand All @@ -132,16 +124,12 @@ LinearFeedbackControllerRos::on_export_reference_interfaces() {

CallbackReturn LinearFeedbackControllerRos::on_configure(
const rclcpp_lifecycle::State& /*previous_state*/) {
// DEBUG
RCLCPP_WARN(get_node()->get_logger(), "Successfull configuration.");
first_time_update_and_write_commands_ = true;
return CallbackReturn::SUCCESS;
}

CallbackReturn LinearFeedbackControllerRos::on_activate(
const rclcpp_lifecycle::State& /*previous_state*/) {
// DEBUG
RCLCPP_WARN(get_node()->get_logger(), "on_activate");
const std::vector<std::string> joint_names =
lfc_.get_robot_model()->get_moving_joint_names();

Expand Down Expand Up @@ -177,8 +165,6 @@ CallbackReturn LinearFeedbackControllerRos::on_activate(
}

bool LinearFeedbackControllerRos::on_set_chained_mode(bool chained_mode) {
// DEBUG
RCLCPP_WARN(get_node()->get_logger(), "on_set_chained_mode");
auto callback =
std::bind(&LinearFeedbackControllerRos::state_syncher_callback, this,
std::placeholders::_1, std::placeholders::_2);
Expand All @@ -192,8 +178,6 @@ bool LinearFeedbackControllerRos::on_set_chained_mode(bool chained_mode) {

CallbackReturn LinearFeedbackControllerRos::on_deactivate(
const rclcpp_lifecycle::State& /*previous_state*/) {
// DEBUG
RCLCPP_WARN(get_node()->get_logger(), "on_deactivate");
// Custom release interfaces for this controller.
joint_position_state_interface_.clear();
joint_velocity_state_interface_.clear();
Expand All @@ -208,8 +192,6 @@ CallbackReturn LinearFeedbackControllerRos::on_deactivate(

CallbackReturn LinearFeedbackControllerRos::on_cleanup(
const rclcpp_lifecycle::State& /*previous_state*/) {
// DEBUG
RCLCPP_WARN(get_node()->get_logger(), "on_cleanup");
// if (parameters_.floating_base_state_estimator.spawn_thread) {
// floating_base_estimator_->joinThread();
// }
Expand Down

0 comments on commit 1f244eb

Please sign in to comment.