Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Formatting changes from pre-commit #400

Merged
merged 1 commit into from
Jul 30, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@ controller_interface::CallbackReturn DiffDriveController::on_init()
auto_declare<bool>("enable_odom_tf", odom_params_.enable_odom_tf);

auto_declare<double>("cmd_vel_timeout", cmd_vel_timeout_.count() / 1000.0);
publish_limited_velocity_ = auto_declare<bool>("publish_limited_velocity",
publish_limited_velocity_);
publish_limited_velocity_ =
auto_declare<bool>("publish_limited_velocity", publish_limited_velocity_);
auto_declare<int>("velocity_rolling_window_size", 10);
use_stamped_vel_ = auto_declare<bool>("use_stamped_vel", use_stamped_vel_);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ class GripperActionController : public controller_interface::ControllerInterface
stall_velocity_threshold_; ///< Stall related parameters
double default_max_effort_; ///< Max allowed effort
double goal_tolerance_;
bool allow_stalling_; ///< If gripper stalls when moving to goal is considered successful
bool allow_stalling_; ///< If gripper stalls when moving to goal is considered successful

/**
* \brief Check for success and publish appropriate result and feedback.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ void GripperActionController<HardwareInterface>::check_for_success(
pre_alloc_result_->position = current_position;
pre_alloc_result_->reached_goal = false;
pre_alloc_result_->stalled = true;
if(allow_stalling_)
if (allow_stalling_)
{
RCLCPP_DEBUG(get_node()->get_logger(), "Stall detected moving to goal. Returning success.");
rt_active_goal_->setSucceeded(pre_alloc_result_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class DoubleEditor(QWidget):
valueChanged = Signal(float)

def __init__(self, min_val, max_val):
super(DoubleEditor, self).__init__()
super().__init__()

# Preconditions
assert min_val < max_val
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from __future__ import print_function
import os
import rclpy
import threading
Expand All @@ -34,7 +33,7 @@
from .update_combo import update_combo

# TODO:
# - Better UI suppor for continuous joints (see DoubleEditor TODO)
# - Better UI support for continuous joints (see DoubleEditor TODO)
# - Can we load controller joints faster?, it's currently pretty slow
# - If URDF is reloaded, allow to reset the whole plugin?
# - Allow to configure:
Expand Down Expand Up @@ -99,7 +98,7 @@ class JointTrajectoryController(Plugin):
jointStateChanged = Signal([dict])

def __init__(self, context):
super(JointTrajectoryController, self).__init__(context)
super().__init__(context)
self.setObjectName('JointTrajectoryController')
self._node = rclpy.node.Node("rqt_joint_trajectory_controller")
self._executor = None
Expand Down Expand Up @@ -204,7 +203,7 @@ def restore_settings(self, plugin_settings, instance_settings):
try:
idx = cm_list.index(cm_ns)
cm_combo.setCurrentIndex(idx)
# Resore last session's controller, if running
# Restore last session's controller, if running
self._update_jtc_list()
jtc_name = instance_settings.value('jtc_name')
jtc_combo = self._widget.jtc_combo
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

# NOTE: The Python API contained in this file is considered UNSTABLE and
# subject to change.
# No backwards compatibility guarrantees are provided at this moment.
# No backwards compatibility guarantees are provided at this moment.


import rclpy
Expand Down