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

Merged in changes from release repository

This commit is contained in:
Felix Mauch
2019-07-16 11:04:04 +02:00
7 changed files with 26 additions and 98 deletions

View File

@@ -4,7 +4,7 @@ hardware_control_loop:
# Settings for ros_control hardware interface
hardware_interface:
joints:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
@@ -31,13 +31,7 @@ speed_scaling_state_controller:
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
@@ -48,18 +42,12 @@ scaled_pos_traj_controller:
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
state_publish_rate: 125
action_monitor_rate: 10
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
@@ -70,5 +58,5 @@ pos_traj_controller:
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
state_publish_rate: 125
action_monitor_rate: 10

View File

@@ -4,7 +4,7 @@ hardware_control_loop:
# Settings for ros_control hardware interface
hardware_interface:
joints:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
@@ -31,13 +31,7 @@ speed_scaling_state_controller:
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
@@ -53,13 +47,7 @@ scaled_pos_traj_controller:
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05

View File

@@ -4,7 +4,7 @@ hardware_control_loop:
# Settings for ros_control hardware interface
hardware_interface:
joints:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
@@ -31,13 +31,7 @@ speed_scaling_state_controller:
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
@@ -48,18 +42,12 @@ scaled_pos_traj_controller:
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
state_publish_rate: 125
action_monitor_rate: 10
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
@@ -70,5 +58,5 @@ pos_traj_controller:
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
state_publish_rate: 125
action_monitor_rate: 10

View File

@@ -4,7 +4,7 @@ hardware_control_loop:
# Settings for ros_control hardware interface
hardware_interface:
joints:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
@@ -31,13 +31,7 @@ speed_scaling_state_controller:
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
@@ -53,13 +47,7 @@ scaled_pos_traj_controller:
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05

View File

@@ -4,7 +4,7 @@ hardware_control_loop:
# Settings for ros_control hardware interface
hardware_interface:
joints:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
@@ -31,13 +31,7 @@ speed_scaling_state_controller:
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
@@ -48,18 +42,12 @@ scaled_pos_traj_controller:
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
state_publish_rate: 125
action_monitor_rate: 10
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
@@ -70,5 +58,5 @@ pos_traj_controller:
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
state_publish_rate: 125
action_monitor_rate: 10

View File

@@ -4,7 +4,7 @@ hardware_control_loop:
# Settings for ros_control hardware interface
hardware_interface:
joints:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
@@ -31,13 +31,7 @@ speed_scaling_state_controller:
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
@@ -53,13 +47,7 @@ scaled_pos_traj_controller:
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05

View File

@@ -67,7 +67,7 @@ bool RTDEClient::init()
tmp_version = dynamic_cast<rtde_interface::RequestProtocolVersion*>(package.get());
if (!tmp_version->accepted_)
{
throw UrException("Neither protocol version 1 nor 2 were accepted by the robot. This should not happen!");
throw UrException("Neither protocol version 1 nor 2 was accepted by the robot. This should not happen!");
}
}
@@ -110,7 +110,7 @@ bool RTDEClient::start()
std::unique_ptr<comm::URPackage<PackageHeader>> package;
stream_.write(buffer, size, written);
if (!pipeline_.getLatestProduct(package, std::chrono::milliseconds(1000)))
throw UrException("Could not get respone to rtde communication start request from robot. This should not happen!");
throw UrException("Could not get response to RTDE communication start request from robot. This should not happen!");
rtde_interface::ControlPackageStart* tmp = dynamic_cast<rtde_interface::ControlPackageStart*>(package.get());
return tmp->accepted_;
}