#include <ros/ros.h>#include <actionlib/client/simple_action_client.h>#include <actionlib/server/simple_action_server.h>#include <boost/foreach.hpp>#include <boost/thread/recursive_mutex.hpp>#include <control_msgs/FollowJointTrajectoryAction.h>#include <control_msgs/GripperCommandAction.h>#include <ecl/geometry.hpp>#include <wpi_jaco_msgs/AngularCommand.h>#include <wpi_jaco_msgs/CartesianCommand.h>#include <wpi_jaco_msgs/EStop.h>#include <wpi_jaco_msgs/GetAngularPosition.h>#include <wpi_jaco_msgs/GetCartesianPosition.h>#include <wpi_jaco_msgs/HomeArmAction.h>#include <wpi_jaco_msgs/JacoFK.h>#include <wpi_jaco_msgs/QuaternionToEuler.h>#include <sensor_msgs/JointState.h>#include <std_msgs/Bool.h>#include <std_srvs/Empty.h>#include <jaco_sdk/Kinova.API.UsbCommandLayerUbuntu.h>

Go to the source code of this file.
Classes | |
| class | jaco::JacoArmTrajectoryController |
Namespaces | |
| namespace | jaco |
Defines | |
| #define | ANGULAR_CONTROL 1 |
| #define | CARTESIAN_CONTROL 2 |
| #define | DEG_TO_RAD (M_PI/180) |
| #define | ERROR_THRESHOLD .03 |
| #define | KI_F 0.1 |
| #define | KP 300.0 |
| #define | KP_F 7.5 |
| #define | KV 20.0 |
| #define | KV_F 0.05 |
| #define | LARGE_ACTUATOR_VELOCITY 0.8378 |
| #define | NO_ERROR 1 |
| #define | NUM_JACO_JOINTS 6 |
| Provides for trajectory execution and gripper control of the JACO arm. | |
| #define | RAD_TO_DEG (180/M_PI) |
| #define | SMALL_ACTUATOR_VELOCITY 1.0472 |
| #define | TIME_SCALING_FACTOR 1.5 |
| #define ANGULAR_CONTROL 1 |
Definition at line 58 of file jaco_arm_trajectory_node.h.
| #define CARTESIAN_CONTROL 2 |
Definition at line 59 of file jaco_arm_trajectory_node.h.
| #define DEG_TO_RAD (M_PI/180) |
Definition at line 44 of file jaco_arm_trajectory_node.h.
| #define ERROR_THRESHOLD .03 |
Definition at line 50 of file jaco_arm_trajectory_node.h.
| #define KI_F 0.1 |
Definition at line 55 of file jaco_arm_trajectory_node.h.
| #define KP 300.0 |
Definition at line 48 of file jaco_arm_trajectory_node.h.
| #define KP_F 7.5 |
Definition at line 53 of file jaco_arm_trajectory_node.h.
| #define KV 20.0 |
Definition at line 49 of file jaco_arm_trajectory_node.h.
| #define KV_F 0.05 |
Definition at line 54 of file jaco_arm_trajectory_node.h.
| #define LARGE_ACTUATOR_VELOCITY 0.8378 |
Definition at line 40 of file jaco_arm_trajectory_node.h.
| #define NO_ERROR 1 |
Definition at line 61 of file jaco_arm_trajectory_node.h.
| #define NUM_JACO_JOINTS 6 |
Provides for trajectory execution and gripper control of the JACO arm.
.h jaco_arm_trajectory_node creates a ROS node that provides trajectory execution and gripper control through the Kinova API, and smooth trajectory following through a velocity controller.
Definition at line 38 of file jaco_arm_trajectory_node.h.
| #define RAD_TO_DEG (180/M_PI) |
Definition at line 45 of file jaco_arm_trajectory_node.h.
| #define SMALL_ACTUATOR_VELOCITY 1.0472 |
Definition at line 41 of file jaco_arm_trajectory_node.h.
| #define TIME_SCALING_FACTOR 1.5 |
Definition at line 42 of file jaco_arm_trajectory_node.h.