mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 11:00:47 +02:00
Added clang formatting
This commit is contained in:
@@ -1,2 +1 @@
|
||||
#pragma once
|
||||
|
||||
|
||||
@@ -1,12 +1,12 @@
|
||||
#pragma once
|
||||
|
||||
#include <cstdlib>
|
||||
#include <vector>
|
||||
#include <ros/ros.h>
|
||||
#include <sensor_msgs/JointState.h>
|
||||
#include <geometry_msgs/WrenchStamped.h>
|
||||
#include <geometry_msgs/PoseStamped.h>
|
||||
#include <geometry_msgs/TwistStamped.h>
|
||||
#include <geometry_msgs/WrenchStamped.h>
|
||||
#include <ros/ros.h>
|
||||
#include <sensor_msgs/JointState.h>
|
||||
#include <vector>
|
||||
|
||||
#include "ur_modern_driver/ur/consumer.h"
|
||||
|
||||
@@ -26,34 +26,34 @@ private:
|
||||
NodeHandle _nh;
|
||||
Publisher _joint_pub;
|
||||
Publisher _wrench_pub;
|
||||
Publisher _tool_vel_pub;
|
||||
Publisher _tool_vel_pub;
|
||||
std::vector<std::string> _joint_names;
|
||||
std::string _base_frame;
|
||||
|
||||
bool publish_joints(RTShared &packet, ros::Time &t);
|
||||
bool publish_wrench(RTShared &packet, ros::Time &t);
|
||||
bool publish_tool(RTShared &packet, ros::Time &t);
|
||||
bool publish_joints(RTShared& packet, ros::Time& t);
|
||||
bool publish_wrench(RTShared& packet, ros::Time& t);
|
||||
bool publish_tool(RTShared& packet, ros::Time& t);
|
||||
|
||||
bool publish(RTShared &packet);
|
||||
bool publish(RTShared& packet);
|
||||
|
||||
public:
|
||||
RTPublisher(std::string &joint_prefix, std::string &base_frame) :
|
||||
_joint_pub(_nh.advertise<sensor_msgs::JointState>("joint_states", 1)),
|
||||
_wrench_pub(_nh.advertise<geometry_msgs::WrenchStamped>("wrench", 1)),
|
||||
_tool_vel_pub(_nh.advertise<geometry_msgs::TwistStamped>("tool_velocity", 1)),
|
||||
_base_frame(base_frame)
|
||||
RTPublisher(std::string& joint_prefix, std::string& base_frame)
|
||||
: _joint_pub(_nh.advertise<sensor_msgs::JointState>("joint_states", 1))
|
||||
, _wrench_pub(_nh.advertise<geometry_msgs::WrenchStamped>("wrench", 1))
|
||||
, _tool_vel_pub(_nh.advertise<geometry_msgs::TwistStamped>("tool_velocity", 1))
|
||||
, _base_frame(base_frame)
|
||||
{
|
||||
for(auto const& j : JOINTS) {
|
||||
for (auto const& j : JOINTS) {
|
||||
_joint_names.push_back(joint_prefix + j);
|
||||
}
|
||||
}
|
||||
|
||||
virtual bool consume(RTState_V1_6__7 &state);
|
||||
virtual bool consume(RTState_V1_8 &state);
|
||||
virtual bool consume(RTState_V3_0__1 &state);
|
||||
virtual bool consume(RTState_V3_2__3 &state);
|
||||
virtual bool consume(RTState_V1_6__7& state);
|
||||
virtual bool consume(RTState_V1_8& state);
|
||||
virtual bool consume(RTState_V3_0__1& state);
|
||||
virtual bool consume(RTState_V3_2__3& state);
|
||||
|
||||
virtual void setup_consumer() { }
|
||||
virtual void teardown_consumer() { }
|
||||
virtual void stop_consumer() { }
|
||||
virtual void setup_consumer() {}
|
||||
virtual void teardown_consumer() {}
|
||||
virtual void stop_consumer() {}
|
||||
};
|
||||
Reference in New Issue
Block a user