Skip to content
Snippets Groups Projects
Commit ea727f7d authored by pre-commit-ci[bot]'s avatar pre-commit-ci[bot] Committed by Florent Lamiraux
Browse files

[pre-commit.ci] auto fixes from pre-commit.com hooks

for more information, see https://pre-commit.ci
parent f7f362df
No related branches found
No related tags found
No related merge requests found
Pipeline #28999 failed
......@@ -16,7 +16,8 @@ inline void RosPublish::sendData<std::pair<sot::MatrixHomogeneous, Vector> >(
publisher,
boost::shared_ptr<
SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::signalIn_t>
signal, sigtime_t time) {
signal,
sigtime_t time) {
SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::ros_t result;
if (publisher->trylock()) {
publisher->msg_.child_frame_id = "/dynamic_graph/world";
......
......@@ -176,8 +176,9 @@ class RosQueuedSubscribe : public dynamicgraph::Entity {
ros::NodeHandle& nh() { return nh_; }
template <typename R, typename S>
void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> >
signal, const R& data);
void callback(
boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> > signal,
const R& data);
template <typename R>
void callbackTimestamp(
......
......@@ -71,8 +71,9 @@ class RosSubscribe : public dynamicgraph::Entity {
ros::NodeHandle& nh() { return nh_; }
template <typename R, typename S>
void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> >
signal, const R& data);
void callback(
boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> > signal,
const R& data);
template <typename R>
void callbackTimestamp(
......
......@@ -18,7 +18,8 @@ namespace dg = dynamicgraph;
namespace dynamicgraph {
template <typename R, typename S>
void RosSubscribe::callback(
boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> > signal, const R& data) {
boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> > signal,
const R& data) {
typedef S sot_t;
sot_t value;
converter(value, data);
......@@ -101,7 +102,8 @@ struct Add<std::pair<T, dg::Vector> > {
RosSubscribe.bindedSignal()[signal] = bindedSignal;
// Timestamp.
typedef dynamicgraph::SignalPtr<RosSubscribe::ptime, sigtime_t> signalTimestamp_t;
typedef dynamicgraph::SignalPtr<RosSubscribe::ptime, sigtime_t>
signalTimestamp_t;
std::string signalTimestamp =
(boost::format("%1%%2%") % signal % "Timestamp").str();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment