diff --git a/include/dynamic_graph_bridge/ros.hpp b/include/dynamic_graph_bridge/ros.hpp index 34ff7ebdef8fd90191bd50cbe95ba16316cc0fcc..bbf1e0ec2d2aa5fcb7af071e18c64ccd41c1036f 100644 --- a/include/dynamic_graph_bridge/ros.hpp +++ b/include/dynamic_graph_bridge/ros.hpp @@ -7,9 +7,8 @@ #pragma once -#include <memory> - #include <boost/chrono.hpp> +#include <memory> // ROS includes #include "dynamic_graph_bridge_msgs/srv/run_python_command.hpp" diff --git a/scripts/remote_python_client.py b/scripts/remote_python_client.py index e3c7023e9c94e02929795dbd7096e6b1016c0512..2fb0432e77aa5c017dd8aaf4ab36d0646bb65dc8 100755 --- a/scripts/remote_python_client.py +++ b/scripts/remote_python_client.py @@ -24,10 +24,10 @@ import sys from pathlib import Path import rclpy -from dynamic_graph_bridge_cpp_bindings import RosPythonInterpreterClient # Used to connect to ROS services from dynamic_graph_bridge.ros.dgcompleter import DGCompleter +from dynamic_graph_bridge_cpp_bindings import RosPythonInterpreterClient def signal_handler(sig, frame): diff --git a/src/dg_ros_mapping.cpp b/src/dg_ros_mapping.cpp index aae712369f4360eaf30a7d29a10375cc91194469..4b491f49c3871f1728062eae42687c2801aea01c 100644 --- a/src/dg_ros_mapping.cpp +++ b/src/dg_ros_mapping.cpp @@ -67,11 +67,10 @@ DG_TO_ROS_IMPL(DgRosMappingMatrix) { // of the copy here. ros_dst.width = static_cast<unsigned int>(dg_src.rows()); ros_dst.data.resize(static_cast<std::size_t>(dg_src.size())); - for (int row = 0 ; row < dg_src.rows(); ++row) { + for (int row = 0; row < dg_src.rows(); ++row) { for (int col = 0; col < dg_src.cols(); ++col) { ros_dst.data[static_cast<unsigned int>(row) * ros_dst.width + - static_cast<unsigned int>(col)] = - dg_src(row, col); + static_cast<unsigned int>(col)] = dg_src(row, col); } } } @@ -84,7 +83,8 @@ ROS_TO_DG_IMPL(DgRosMappingMatrix) { for (int row = 0; row < dg_dst.rows(); ++row) { for (int col = 0; col < dg_dst.cols(); ++col) { dg_dst(row, col) = - ros_src.data[static_cast<std::vector<double>::size_type>(row * rows + col)]; + ros_src.data[static_cast<std::vector<double>::size_type>(row * rows + + col)]; } } } diff --git a/src/dg_ros_mapping.hpp b/src/dg_ros_mapping.hpp index b9dd8db479402f72a55f5f3d99ef909969127c07..a093667f9d6b4c3195983cf7f017f1a2924e5fb4 100644 --- a/src/dg_ros_mapping.hpp +++ b/src/dg_ros_mapping.hpp @@ -11,12 +11,11 @@ #include "fwd.hpp" // Standard includes +#include <boost/chrono.hpp> #include <sstream> #include <utility> #include <vector> -#include <boost/chrono.hpp> - // Dynamic Graph types. #include <dynamic-graph/linear-algebra.h> #include <dynamic-graph/signal-ptr.h> @@ -111,7 +110,8 @@ class DgRosMapping { /** @brief Output signal type. */ typedef dg::SignalTimeDependent<dg_t, dg::sigtime_t> signal_out_t; /** @brief Output signal type. */ - typedef dg::SignalTimeDependent<dynamic_graph_bridge::timestamp_t, dg::sigtime_t> + typedef dg::SignalTimeDependent<dynamic_graph_bridge::timestamp_t, + dg::sigtime_t> signal_timestamp_out_t; /** @brief Input signal type. */ typedef dg::SignalPtr<dg_t, dg::sigtime_t> signal_in_t; @@ -138,9 +138,7 @@ class DgRosMapping { * * @param s */ - static void set_default(dg_t& d) { - d = default_value; - } + static void set_default(dg_t& d) { d = default_value; } /** * @brief Convert ROS time to boost::chrono. diff --git a/src/fwd.hpp b/src/fwd.hpp index bb7d3ab5009746a66c021756e333e557a99b1645..e932d1713e8859ccfbef144d4cf3528923d0f143 100644 --- a/src/fwd.hpp +++ b/src/fwd.hpp @@ -10,18 +10,19 @@ #pragma once +#include <boost/chrono.hpp> #include <chrono> -#include <ostream> #include <iostream> -#include <boost/chrono.hpp> +#include <ostream> namespace dynamic_graph_bridge { /** @brief Time stamp type. */ -typedef boost::chrono::time_point<boost::chrono::high_resolution_clock> timestamp_t; +typedef boost::chrono::time_point<boost::chrono::high_resolution_clock> + timestamp_t; } // namespace dynamic_graph_bridge -//namespace dynamicgraph { +// namespace dynamicgraph { /** * @brief out stream the time stamp data. * @@ -32,16 +33,15 @@ typedef boost::chrono::time_point<boost::chrono::high_resolution_clock> timestam * For clang this function needs to be forward declared before the template * using it. This is more in accordance to the standard. */ -std::ostream &operator<<( - std::ostream &os, - const dynamic_graph_bridge::timestamp_t &time_stamp) { +std::ostream &operator<<(std::ostream &os, + const dynamic_graph_bridge::timestamp_t &time_stamp) { boost::chrono::time_point<boost::chrono::high_resolution_clock, - boost::chrono::milliseconds> + boost::chrono::milliseconds> time_stamp_nanosec = - boost::chrono::time_point_cast<boost::chrono::milliseconds>(time_stamp); + boost::chrono::time_point_cast<boost::chrono::milliseconds>( + time_stamp); os << time_stamp_nanosec.time_since_epoch().count(); return os; } - //} // namespace dynamicgraph diff --git a/src/ros_python_interpreter_client.cpp b/src/ros_python_interpreter_client.cpp index 1a9c05296693ed771c8c944f4a0604ae536a1207..ee4f75a7d3f90485cd962e66445c7c838a76b55f 100644 --- a/src/ros_python_interpreter_client.cpp +++ b/src/ros_python_interpreter_client.cpp @@ -71,7 +71,8 @@ std::string RosPythonInterpreterClient::run_python_command( return_string += response.get()->result; } } catch (const std::exception& ex) { - RCLCPP_INFO(rclcpp::get_logger("RosPythonInterpreterClient"), "%s", ex.what()); + RCLCPP_INFO(rclcpp::get_logger("RosPythonInterpreterClient"), "%s", + ex.what()); connect_to_rosservice_run_python_command(timeout_connection_s_); } catch (...) { RCLCPP_INFO(rclcpp::get_logger("RosPythonInterpreterClient"), diff --git a/src/ros_subscribe.cpp b/src/ros_subscribe.cpp index ea750604689f6370db2abc7b200165faf7a97b31..907212344b1d299a339b78306461fccdad7376b1 100644 --- a/src/ros_subscribe.cpp +++ b/src/ros_subscribe.cpp @@ -6,12 +6,11 @@ * Gesellschaft. * @date 2019-05-22 */ -#include "fwd.hpp" - #include "ros_subscribe.hpp" #include <dynamic-graph/factory.h> +#include "fwd.hpp" namespace dynamic_graph_bridge { /* diff --git a/src/ros_subscribe.hpp b/src/ros_subscribe.hpp index 4285d2b1048f165cb416d84e4b4e54ca216fdf6e..7be1d0e045c28526833a6d32e19622afb7e7623d 100644 --- a/src/ros_subscribe.hpp +++ b/src/ros_subscribe.hpp @@ -127,7 +127,6 @@ class RosSubscribe : public dynamicgraph::Entity { std::map<std::string, BindedSignal> binded_signals_; }; - namespace command { namespace ros_subscribe { using ::dynamicgraph::command::Command; diff --git a/src/sot_loader.cpp b/src/sot_loader.cpp index bb7a5390a4cf0320bb406e6c28527f1d85216448..6f560663bcfe06beb19f333d8367d63199c4c206 100644 --- a/src/sot_loader.cpp +++ b/src/sot_loader.cpp @@ -137,7 +137,7 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) { sotDEBUG(30) << "End ControlValues" << std::endl; #endif std::size_t nbOfJoints_std_s = static_cast<std::size_t>(nbOfJoints_); - + // Check if the size if coherent with the robot description. if (control_.size() != (unsigned int)nbOfJoints_) { nbOfJoints_ = static_cast<int>(control_.size()); @@ -151,7 +151,7 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) { if (joint_state_.position.size() != static_cast<std::size_t>(nbOfJoints_) + - parallel_joints_to_state_vector_.size()) { + parallel_joints_to_state_vector_.size()) { joint_state_.position.resize(nbOfJoints_std_s + parallel_joints_to_state_vector_.size()); joint_state_.velocity.resize(nbOfJoints_std_s + @@ -170,7 +170,8 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) { for (unsigned int i = 0; i < parallel_joints_to_state_vector_.size(); i++) { joint_state_.position[i + nbOfJoints_std_s] = coefficient_parallel_joints_[i] * - angleEncoder_[static_cast<std::size_t>(parallel_joints_to_state_vector_[i])]; + angleEncoder_[static_cast<std::size_t>( + parallel_joints_to_state_vector_[i])]; } joint_pub_->publish(joint_state_); @@ -230,8 +231,7 @@ void SotLoader::workThreadLoader() { /// Declare parameters if (not has_parameter("dt")) declare_parameter<double>("dt", 0.01); - if (not has_parameter("paused")) - declare_parameter<bool>("paused", false); + if (not has_parameter("paused")) declare_parameter<bool>("paused", false); // get_parameter_or("dt", periodd, 0.001); diff --git a/tests/impl_test_sot_mock_device.cpp b/tests/impl_test_sot_mock_device.cpp index 3d85fe286c3e9a9db86455873cb0b884b28bf38c..1bd8e492a23b2b797e0a44ef4a4df396ee35e81d 100644 --- a/tests/impl_test_sot_mock_device.cpp +++ b/tests/impl_test_sot_mock_device.cpp @@ -117,8 +117,8 @@ void ImplTestSotMockDevice::setSensorsForce( sotDEBUG(15) << "Force sensor " << i << std::endl; int idx_sensor = map_sot_2_urdf[i]; for (std::vector<double>::size_type j = 0; j < 6; ++j) { - dgforces_(static_cast<Eigen::Index>(j)) = - forcesIn[static_cast<std::vector<double>::size_type>(idx_sensor * 6) + j]; + dgforces_(static_cast<Eigen::Index>(j)) = forcesIn + [static_cast<std::vector<double>::size_type>(idx_sensor * 6) + j]; sotDEBUG(15) << "Force value " << j << ":" << dgforces_(static_cast<Eigen::Index>(j)) << std::endl; } @@ -202,7 +202,8 @@ void ImplTestSotMockDevice::setSensorsVelocities( const vector<double>& velocitiesIn = it->second.getValues(); dgRobotVelocity_.resize(static_cast<Eigen::Index>(velocitiesIn.size()) + 6); for (unsigned i = 0; i < 6; ++i) dgRobotVelocity_(i) = 0.; - for (unsigned i = 0; i < static_cast<Eigen::Index>(velocitiesIn.size()); ++i) { + for (unsigned i = 0; i < static_cast<Eigen::Index>(velocitiesIn.size()); + ++i) { dgRobotVelocity_(i + 6) = velocitiesIn[i]; } robotVelocity_.setConstant(dgRobotVelocity_); @@ -298,7 +299,8 @@ void ImplTestSotMockDevice::getControl( sotDEBUGIN(25); vector<double> anglesOut, velocityOut; anglesOut.resize(static_cast<std::vector<double>::size_type>(state_.size())); - velocityOut.resize(static_cast<std::vector<double>::size_type>(state_.size())); + velocityOut.resize( + static_cast<std::vector<double>::size_type>(state_.size())); // Integrate control sotDEBUG(25) << "state = " << state_ << std::endl; @@ -317,8 +319,10 @@ void ImplTestSotMockDevice::getControl( // warning: we make here the asumption that the control signal contains the // velocity of the freeflyer joint. This may change in the future. if ((int)anglesOut.size() != state_.size() - 6) { - anglesOut.resize(static_cast<std::vector<double>::size_type>(state_.size() - 6)); - velocityOut.resize(static_cast<std::vector<double>::size_type>(state_.size() - 6)); + anglesOut.resize( + static_cast<std::vector<double>::size_type>(state_.size() - 6)); + velocityOut.resize( + static_cast<std::vector<double>::size_type>(state_.size() - 6)); } dg::sigtime_t time = controlSIN.getTime(); diff --git a/tests/launch/launching_test_sot_loader_basic.py b/tests/launch/launching_test_sot_loader_basic.py index 7ef3489c96c6eebef9a87316e5d0a1023f645116..3ae842710e88d7817a0bda1eae0510368b0c7b11 100644 --- a/tests/launch/launching_test_sot_loader_basic.py +++ b/tests/launch/launching_test_sot_loader_basic.py @@ -55,7 +55,7 @@ def generate_test_description(): {"state_vector_map": ["joint1", "joint2"]}, {"robot_description": robot_description_content}, ], - arguments=['--ros-args', '--log-level', 'INFO'] + arguments=["--ros-args", "--log-level", "INFO"], ) return (