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,6 @@
#include <ros/ros.h>
#include <chrono>
#include <cstdlib>
#include <ros/ros.h>
#include <string>
#include <thread>
@@ -21,55 +21,59 @@ static const std::string PREFIX_ARG("~prefix");
static const std::string BASE_FRAME_ARG("~base_frame");
static const std::string TOOL_FRAME_ARG("~tool_frame");
struct ProgArgs {
struct ProgArgs
{
public:
std::string host;
std::string prefix;
std::string base_frame;
std::string tool_frame;
int32_t reverse_port;
bool use_sim_time;
std::string host;
std::string prefix;
std::string base_frame;
std::string tool_frame;
int32_t reverse_port;
bool use_sim_time;
};
bool parse_args(ProgArgs& args)
{
if (!ros::param::get(IP_ADDR_ARG, args.host)) {
LOG_ERROR("robot_ip_address parameter must be set!");
return false;
}
ros::param::param(REVERSE_PORT_ARG, args.reverse_port, int32_t(50001));
ros::param::param(SIM_TIME_ARG, args.use_sim_time, false);
ros::param::param(PREFIX_ARG, args.prefix, std::string());
ros::param::param(BASE_FRAME_ARG, args.base_frame, args.prefix + "base_link");
ros::param::param(TOOL_FRAME_ARG, args.tool_frame, args.prefix + "tool0_controller");
return true;
if (!ros::param::get(IP_ADDR_ARG, args.host))
{
LOG_ERROR("robot_ip_address parameter must be set!");
return false;
}
ros::param::param(REVERSE_PORT_ARG, args.reverse_port, int32_t(50001));
ros::param::param(SIM_TIME_ARG, args.use_sim_time, false);
ros::param::param(PREFIX_ARG, args.prefix, std::string());
ros::param::param(BASE_FRAME_ARG, args.base_frame, args.prefix + "base_link");
ros::param::param(TOOL_FRAME_ARG, args.tool_frame, args.prefix + "tool0_controller");
return true;
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "ur_driver");
ros::init(argc, argv, "ur_driver");
ProgArgs args;
if (!parse_args(args)) {
return EXIT_FAILURE;
}
ProgArgs args;
if (!parse_args(args))
{
return EXIT_FAILURE;
}
URFactory factory(args.host);
auto parser = factory.get_rt_parser();
URFactory factory(args.host);
auto parser = factory.getRTParser();
URStream s2(args.host, 30003);
URProducer<RTPacket> p2(s2, *parser);
RTPublisher pub(args.prefix, args.base_frame, args.tool_frame);
URStream s2(args.host, 30003);
URProducer<RTPacket> p2(s2, *parser);
RTPublisher pub(args.prefix, args.base_frame, args.tool_frame);
Pipeline<RTPacket> pl(p2, pub);
Pipeline<RTPacket> pl(p2, pub);
pl.run();
pl.run();
while (ros::ok()) {
std::this_thread::sleep_for(std::chrono::milliseconds(33));
}
while (ros::ok())
{
std::this_thread::sleep_for(std::chrono::milliseconds(33));
}
pl.stop();
pl.stop();
return EXIT_SUCCESS;
return EXIT_SUCCESS;
}