1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 10:00:48 +02:00

Adopted roscpp code style and naming convention

This commit is contained in:
Simon Rasmussen
2017-03-01 13:59:48 +01:00
parent e4bc40fc09
commit 474f469e97
44 changed files with 5097 additions and 4891 deletions

View File

@@ -1,6 +1,5 @@
#pragma once
#include <cstdlib>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/TwistStamped.h>
#include <geometry_msgs/WrenchStamped.h>
@@ -9,6 +8,7 @@
#include <sensor_msgs/Temperature.h>
#include <tf/tf.h>
#include <tf/transform_broadcaster.h>
#include <cstdlib>
#include <vector>
#include "ur_modern_driver/ur/consumer.h"
@@ -16,55 +16,57 @@
using namespace ros;
using namespace tf;
const std::string JOINTS[] = {
"shoulder_pan_joint",
"shoulder_lift_joint",
"elbow_joint",
"wrist_1_joint",
"wrist_2_joint",
"wrist_3_joint"
};
const std::string JOINTS[] = { "shoulder_pan_joint", "shoulder_lift_joint", "elbow_joint",
"wrist_1_joint", "wrist_2_joint", "wrist_3_joint" };
class RTPublisher : public URRTPacketConsumer {
class RTPublisher : public URRTPacketConsumer
{
private:
NodeHandle _nh;
Publisher _joint_pub;
Publisher _wrench_pub;
Publisher _tool_vel_pub;
Publisher _joint_temperature_pub;
TransformBroadcaster _transform_broadcaster;
std::vector<std::string> _joint_names;
std::string _base_frame;
std::string _tool_frame;
NodeHandle nh_;
Publisher joint_pub_;
Publisher wrench_pub_;
Publisher tool_vel_pub_;
Publisher joint_temperature_pub_;
TransformBroadcaster transform_broadcaster_;
std::vector<std::string> joint_names_;
std::string base_frame_;
std::string tool_frame_;
bool publish_joints(RTShared& packet, Time& t);
bool publish_wrench(RTShared& packet, Time& t);
bool publish_tool(RTShared& packet, Time& t);
bool publish_transform(RTShared& packet, Time& t);
bool publish_temperature(RTShared& packet, Time& t);
bool publishJoints(RTShared& packet, Time& t);
bool publishWrench(RTShared& packet, Time& t);
bool publishTool(RTShared& packet, Time& t);
bool publishTransform(RTShared& packet, Time& t);
bool publishTemperature(RTShared& packet, Time& t);
bool publish(RTShared& packet);
bool publish(RTShared& packet);
public:
RTPublisher(std::string& joint_prefix, std::string& base_frame, std::string& tool_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))
, _joint_temperature_pub(_nh.advertise<sensor_msgs::Temperature>("joint_temperature", 1))
, _base_frame(base_frame)
, _tool_frame(tool_frame)
RTPublisher(std::string& joint_prefix, std::string& base_frame, std::string& tool_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))
, joint_temperature_pub_(nh_.advertise<sensor_msgs::Temperature>("joint_temperature", 1))
, base_frame_(base_frame)
, tool_frame_(tool_frame)
{
for (auto const& j : JOINTS)
{
for (auto const& j : JOINTS) {
_joint_names.push_back(joint_prefix + j);
}
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 setupConsumer()
{
}
virtual void teardownConsumer()
{
}
virtual void stopConsumer()
{
}
};