mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Renamed Safe Trajectory Follower to Low Bandwidth one
This commit is contained in:
@@ -13,7 +13,7 @@
|
||||
#include "ur_modern_driver/ros/rt_publisher.h"
|
||||
#include "ur_modern_driver/ros/service_stopper.h"
|
||||
#include "ur_modern_driver/ros/trajectory_follower.h"
|
||||
#include "ur_modern_driver/ros/safe_trajectory_follower.h"
|
||||
#include "ur_modern_driver/ros/lowbandwidth_trajectory_follower.h"
|
||||
#include "ur_modern_driver/ros/urscript_handler.h"
|
||||
#include "ur_modern_driver/ur/commander.h"
|
||||
#include "ur_modern_driver/ur/factory.h"
|
||||
@@ -26,7 +26,7 @@
|
||||
static const std::string IP_ADDR_ARG("~robot_ip_address");
|
||||
static const std::string REVERSE_PORT_ARG("~reverse_port");
|
||||
static const std::string ROS_CONTROL_ARG("~use_ros_control");
|
||||
static const std::string SAFE_TRAJECTORY_FOLLOWER("~use_safe_trajectory_follower");
|
||||
static const std::string LOW_BANDWIDTH_TRAJECTORY_FOLLOWER("~use_lowbandwidth_trajectory_follower");
|
||||
static const std::string MAX_VEL_CHANGE_ARG("~max_vel_change");
|
||||
static const std::string PREFIX_ARG("~prefix");
|
||||
static const std::string BASE_FRAME_ARG("~base_frame");
|
||||
@@ -55,7 +55,7 @@ public:
|
||||
double max_vel_change;
|
||||
int32_t reverse_port;
|
||||
bool use_ros_control;
|
||||
bool use_safe_trajectory_follower;
|
||||
bool use_lowbandwidth_trajectory_follower;
|
||||
bool shutdown_on_disconnect;
|
||||
};
|
||||
|
||||
@@ -95,7 +95,7 @@ bool parse_args(ProgArgs &args)
|
||||
ros::param::param(MAX_VEL_CHANGE_ARG, args.max_vel_change, 15.0); // rad/s
|
||||
ros::param::param(MAX_VEL_CHANGE_ARG, args.max_velocity, 10.0);
|
||||
ros::param::param(ROS_CONTROL_ARG, args.use_ros_control, false);
|
||||
ros::param::param(SAFE_TRAJECTORY_FOLLOWER, args.use_safe_trajectory_follower, false);
|
||||
ros::param::param(LOW_BANDWIDTH_TRAJECTORY_FOLLOWER, args.use_lowbandwidth_trajectory_follower, 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");
|
||||
@@ -140,10 +140,10 @@ int main(int argc, char **argv)
|
||||
|
||||
TrajectoryFollowerInterface *traj_follower(nullptr);
|
||||
|
||||
if (args.use_safe_trajectory_follower && !args.use_ros_control)
|
||||
if (args.use_lowbandwidth_trajectory_follower && !args.use_ros_control)
|
||||
{
|
||||
LOG_INFO("Use safe trajectory follower");
|
||||
traj_follower = new SafeTrajectoryFollower(*rt_commander, local_ip, args.reverse_port,factory.isVersion3());
|
||||
LOG_INFO("Use low bandwidth trajectory follower");
|
||||
traj_follower = new LowBandwidthTrajectoryFollower(*rt_commander, local_ip, args.reverse_port,factory.isVersion3());
|
||||
// We are leaking the follower here, but it's OK as this is once-a-lifetime event
|
||||
}
|
||||
else
|
||||
|
||||
Reference in New Issue
Block a user