Skip to content

Commit

Permalink
fix wrong copy-paste + missing word and typo in comment
Browse files Browse the repository at this point in the history
  • Loading branch information
Felix Maisonneuve committed Aug 16, 2021
1 parent 5511776 commit c11af0f
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 10 deletions.
15 changes: 7 additions & 8 deletions kortex_examples/src/full_arm/example_full_arm_movement.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -215,8 +215,7 @@ bool example_send_joint_angles(ros::NodeHandle n, const std::string &robot_name,
}

// Each AngularWaypoint needs a duration and the global duration (from WaypointList) is disregarded.
// If you put 0 to the global duration, the trajectory will be optimal.
// If you somehting too small (for either global duration or AngularWaypoint duration), the trajectory will be rejected.
// If you put something too small (for either global duration or AngularWaypoint duration), the trajectory will be rejected.
int angular_duration = 0;
angularWaypoint.duration = angular_duration;

Expand Down Expand Up @@ -316,11 +315,7 @@ bool example_cartesian_waypoint(ros::NodeHandle n, const std::string &robot_name

last_action_notification_event = 0;

if (service_client_execute_waypoints_trajectory.call(service_execute_waypoints_trajectory))
{
ROS_INFO("The WaypointList command was sent to the robot.");
}
else
if (!service_client_get_config.call(service_get_config))
{
std::string error_string = "Failed to call GetProductConfiguration";
ROS_ERROR("%s", error_string.c_str());
Expand Down Expand Up @@ -350,7 +345,11 @@ bool example_cartesian_waypoint(ros::NodeHandle n, const std::string &robot_name
service_execute_waypoints_trajectory.request.input.duration = 0;
service_execute_waypoints_trajectory.request.input.use_optimal_blending = 0;

if (!service_client_execute_waypoints_trajectory.call(service_execute_waypoints_trajectory))
if (service_client_execute_waypoints_trajectory.call(service_execute_waypoints_trajectory))
{
ROS_INFO("The WaypointList command was sent to the robot.");
}
else
{
std::string error_string = "Failed to call ExecuteWaypointTrajectory";
ROS_ERROR("%s", error_string.c_str());
Expand Down
3 changes: 1 addition & 2 deletions kortex_examples/src/full_arm/example_full_arm_movement.py
Original file line number Diff line number Diff line change
Expand Up @@ -224,8 +224,7 @@ def example_send_joint_angles(self):
angularWaypoint.angles.append(0.0)

# Each AngularWaypoint needs a duration and the global duration (from WaypointList) is disregarded.
# If you put 0 to the global duration, the trajectory will be optimal.
# If you somehting too small (for either global duration or AngularWaypoint duration), the trajectory will be rejected.
# If you put something too small (for either global duration or AngularWaypoint duration), the trajectory will be rejected.
angular_duration = 0
angularWaypoint.duration = angular_duration

Expand Down

0 comments on commit c11af0f

Please sign in to comment.