Skip to content

Commit 8961271

Browse files
pre-commit-ci[bot]olivier-stasse
authored andcommitted
[pre-commit.ci] auto fixes from pre-commit.com hooks
for more information, see https://pre-commit.ci
1 parent 9ad64ef commit 8961271

11 files changed

+39
-39
lines changed

include/dynamic_graph_bridge/ros.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,9 +7,8 @@
77

88
#pragma once
99

10-
#include <memory>
11-
1210
#include <boost/chrono.hpp>
11+
#include <memory>
1312

1413
// ROS includes
1514
#include "dynamic_graph_bridge_msgs/srv/run_python_command.hpp"

scripts/remote_python_client.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,10 +24,10 @@
2424
from pathlib import Path
2525

2626
import rclpy
27-
from dynamic_graph_bridge_cpp_bindings import RosPythonInterpreterClient
2827

2928
# Used to connect to ROS services
3029
from dynamic_graph_bridge.ros.dgcompleter import DGCompleter
30+
from dynamic_graph_bridge_cpp_bindings import RosPythonInterpreterClient
3131

3232

3333
def signal_handler(sig, frame):

src/dg_ros_mapping.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -67,11 +67,10 @@ DG_TO_ROS_IMPL(DgRosMappingMatrix) {
6767
// of the copy here.
6868
ros_dst.width = static_cast<unsigned int>(dg_src.rows());
6969
ros_dst.data.resize(static_cast<std::size_t>(dg_src.size()));
70-
for (int row = 0 ; row < dg_src.rows(); ++row) {
70+
for (int row = 0; row < dg_src.rows(); ++row) {
7171
for (int col = 0; col < dg_src.cols(); ++col) {
7272
ros_dst.data[static_cast<unsigned int>(row) * ros_dst.width +
73-
static_cast<unsigned int>(col)] =
74-
dg_src(row, col);
73+
static_cast<unsigned int>(col)] = dg_src(row, col);
7574
}
7675
}
7776
}
@@ -84,7 +83,8 @@ ROS_TO_DG_IMPL(DgRosMappingMatrix) {
8483
for (int row = 0; row < dg_dst.rows(); ++row) {
8584
for (int col = 0; col < dg_dst.cols(); ++col) {
8685
dg_dst(row, col) =
87-
ros_src.data[static_cast<std::vector<double>::size_type>(row * rows + col)];
86+
ros_src.data[static_cast<std::vector<double>::size_type>(row * rows +
87+
col)];
8888
}
8989
}
9090
}

src/dg_ros_mapping.hpp

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -11,12 +11,11 @@
1111
#include "fwd.hpp"
1212

1313
// Standard includes
14+
#include <boost/chrono.hpp>
1415
#include <sstream>
1516
#include <utility>
1617
#include <vector>
1718

18-
#include <boost/chrono.hpp>
19-
2019
// Dynamic Graph types.
2120
#include <dynamic-graph/linear-algebra.h>
2221
#include <dynamic-graph/signal-ptr.h>
@@ -111,7 +110,8 @@ class DgRosMapping {
111110
/** @brief Output signal type. */
112111
typedef dg::SignalTimeDependent<dg_t, dg::sigtime_t> signal_out_t;
113112
/** @brief Output signal type. */
114-
typedef dg::SignalTimeDependent<dynamic_graph_bridge::timestamp_t, dg::sigtime_t>
113+
typedef dg::SignalTimeDependent<dynamic_graph_bridge::timestamp_t,
114+
dg::sigtime_t>
115115
signal_timestamp_out_t;
116116
/** @brief Input signal type. */
117117
typedef dg::SignalPtr<dg_t, dg::sigtime_t> signal_in_t;
@@ -138,9 +138,7 @@ class DgRosMapping {
138138
*
139139
* @param s
140140
*/
141-
static void set_default(dg_t& d) {
142-
d = default_value;
143-
}
141+
static void set_default(dg_t& d) { d = default_value; }
144142

145143
/**
146144
* @brief Convert ROS time to boost::chrono.

src/fwd.hpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -10,18 +10,19 @@
1010

1111
#pragma once
1212

13+
#include <boost/chrono.hpp>
1314
#include <chrono>
14-
#include <ostream>
1515
#include <iostream>
16-
#include <boost/chrono.hpp>
16+
#include <ostream>
1717

1818
namespace dynamic_graph_bridge {
1919
/** @brief Time stamp type. */
20-
typedef boost::chrono::time_point<boost::chrono::high_resolution_clock> timestamp_t;
20+
typedef boost::chrono::time_point<boost::chrono::high_resolution_clock>
21+
timestamp_t;
2122

2223
} // namespace dynamic_graph_bridge
2324

24-
//namespace dynamicgraph {
25+
// namespace dynamicgraph {
2526
/**
2627
* @brief out stream the time stamp data.
2728
*
@@ -32,16 +33,15 @@ typedef boost::chrono::time_point<boost::chrono::high_resolution_clock> timestam
3233
* For clang this function needs to be forward declared before the template
3334
* using it. This is more in accordance to the standard.
3435
*/
35-
std::ostream &operator<<(
36-
std::ostream &os,
37-
const dynamic_graph_bridge::timestamp_t &time_stamp) {
36+
std::ostream &operator<<(std::ostream &os,
37+
const dynamic_graph_bridge::timestamp_t &time_stamp) {
3838
boost::chrono::time_point<boost::chrono::high_resolution_clock,
39-
boost::chrono::milliseconds>
39+
boost::chrono::milliseconds>
4040
time_stamp_nanosec =
41-
boost::chrono::time_point_cast<boost::chrono::milliseconds>(time_stamp);
41+
boost::chrono::time_point_cast<boost::chrono::milliseconds>(
42+
time_stamp);
4243
os << time_stamp_nanosec.time_since_epoch().count();
4344
return os;
4445
}
4546

46-
4747
//} // namespace dynamicgraph

src/ros_python_interpreter_client.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,8 @@ std::string RosPythonInterpreterClient::run_python_command(
7171
return_string += response.get()->result;
7272
}
7373
} catch (const std::exception& ex) {
74-
RCLCPP_INFO(rclcpp::get_logger("RosPythonInterpreterClient"), "%s", ex.what());
74+
RCLCPP_INFO(rclcpp::get_logger("RosPythonInterpreterClient"), "%s",
75+
ex.what());
7576
connect_to_rosservice_run_python_command(timeout_connection_s_);
7677
} catch (...) {
7778
RCLCPP_INFO(rclcpp::get_logger("RosPythonInterpreterClient"),

src/ros_subscribe.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,12 +6,11 @@
66
* Gesellschaft.
77
* @date 2019-05-22
88
*/
9-
#include "fwd.hpp"
10-
119
#include "ros_subscribe.hpp"
1210

1311
#include <dynamic-graph/factory.h>
1412

13+
#include "fwd.hpp"
1514

1615
namespace dynamic_graph_bridge {
1716
/*

src/ros_subscribe.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -127,7 +127,6 @@ class RosSubscribe : public dynamicgraph::Entity {
127127
std::map<std::string, BindedSignal> binded_signals_;
128128
};
129129

130-
131130
namespace command {
132131
namespace ros_subscribe {
133132
using ::dynamicgraph::command::Command;

src/sot_loader.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) {
137137
sotDEBUG(30) << "End ControlValues" << std::endl;
138138
#endif
139139
std::size_t nbOfJoints_std_s = static_cast<std::size_t>(nbOfJoints_);
140-
140+
141141
// Check if the size if coherent with the robot description.
142142
if (control_.size() != (unsigned int)nbOfJoints_) {
143143
nbOfJoints_ = static_cast<int>(control_.size());
@@ -151,7 +151,7 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) {
151151

152152
if (joint_state_.position.size() !=
153153
static_cast<std::size_t>(nbOfJoints_) +
154-
parallel_joints_to_state_vector_.size()) {
154+
parallel_joints_to_state_vector_.size()) {
155155
joint_state_.position.resize(nbOfJoints_std_s +
156156
parallel_joints_to_state_vector_.size());
157157
joint_state_.velocity.resize(nbOfJoints_std_s +
@@ -170,7 +170,8 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) {
170170
for (unsigned int i = 0; i < parallel_joints_to_state_vector_.size(); i++) {
171171
joint_state_.position[i + nbOfJoints_std_s] =
172172
coefficient_parallel_joints_[i] *
173-
angleEncoder_[static_cast<std::size_t>(parallel_joints_to_state_vector_[i])];
173+
angleEncoder_[static_cast<std::size_t>(
174+
parallel_joints_to_state_vector_[i])];
174175
}
175176

176177
joint_pub_->publish(joint_state_);
@@ -230,8 +231,7 @@ void SotLoader::workThreadLoader() {
230231

231232
/// Declare parameters
232233
if (not has_parameter("dt")) declare_parameter<double>("dt", 0.01);
233-
if (not has_parameter("paused"))
234-
declare_parameter<bool>("paused", false);
234+
if (not has_parameter("paused")) declare_parameter<bool>("paused", false);
235235

236236
//
237237
get_parameter_or("dt", periodd, 0.001);

tests/impl_test_sot_mock_device.cpp

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -117,8 +117,8 @@ void ImplTestSotMockDevice::setSensorsForce(
117117
sotDEBUG(15) << "Force sensor " << i << std::endl;
118118
int idx_sensor = map_sot_2_urdf[i];
119119
for (std::vector<double>::size_type j = 0; j < 6; ++j) {
120-
dgforces_(static_cast<Eigen::Index>(j)) =
121-
forcesIn[static_cast<std::vector<double>::size_type>(idx_sensor * 6) + j];
120+
dgforces_(static_cast<Eigen::Index>(j)) = forcesIn
121+
[static_cast<std::vector<double>::size_type>(idx_sensor * 6) + j];
122122
sotDEBUG(15) << "Force value " << j << ":"
123123
<< dgforces_(static_cast<Eigen::Index>(j)) << std::endl;
124124
}
@@ -202,7 +202,8 @@ void ImplTestSotMockDevice::setSensorsVelocities(
202202
const vector<double>& velocitiesIn = it->second.getValues();
203203
dgRobotVelocity_.resize(static_cast<Eigen::Index>(velocitiesIn.size()) + 6);
204204
for (unsigned i = 0; i < 6; ++i) dgRobotVelocity_(i) = 0.;
205-
for (unsigned i = 0; i < static_cast<Eigen::Index>(velocitiesIn.size()); ++i) {
205+
for (unsigned i = 0; i < static_cast<Eigen::Index>(velocitiesIn.size());
206+
++i) {
206207
dgRobotVelocity_(i + 6) = velocitiesIn[i];
207208
}
208209
robotVelocity_.setConstant(dgRobotVelocity_);
@@ -298,7 +299,8 @@ void ImplTestSotMockDevice::getControl(
298299
sotDEBUGIN(25);
299300
vector<double> anglesOut, velocityOut;
300301
anglesOut.resize(static_cast<std::vector<double>::size_type>(state_.size()));
301-
velocityOut.resize(static_cast<std::vector<double>::size_type>(state_.size()));
302+
velocityOut.resize(
303+
static_cast<std::vector<double>::size_type>(state_.size()));
302304

303305
// Integrate control
304306
sotDEBUG(25) << "state = " << state_ << std::endl;
@@ -317,8 +319,10 @@ void ImplTestSotMockDevice::getControl(
317319
// warning: we make here the asumption that the control signal contains the
318320
// velocity of the freeflyer joint. This may change in the future.
319321
if ((int)anglesOut.size() != state_.size() - 6) {
320-
anglesOut.resize(static_cast<std::vector<double>::size_type>(state_.size() - 6));
321-
velocityOut.resize(static_cast<std::vector<double>::size_type>(state_.size() - 6));
322+
anglesOut.resize(
323+
static_cast<std::vector<double>::size_type>(state_.size() - 6));
324+
velocityOut.resize(
325+
static_cast<std::vector<double>::size_type>(state_.size() - 6));
322326
}
323327

324328
dg::sigtime_t time = controlSIN.getTime();

0 commit comments

Comments
 (0)