Coder Social home page Coder Social logo

kinovarobotics / kinova-ros Goto Github PK

View Code? Open in Web Editor NEW
346.0 27.0 313.0 51.25 MB

ROS packages for Jaco2 and Mico robotic arms

License: BSD 3-Clause "New" or "Revised" License

CMake 0.40% Python 1.07% C++ 89.56% HTML 6.30% CSS 0.58% JavaScript 0.77% Shell 0.02% C 1.30%

kinova-ros's Introduction

Table of Contents

Important

This repository contains source code and configuration files to support the Jaco, Jaco2 and Mico arms in ROS.

This repository doesn't support the Gen3 arm in ROS. Have a look at the ros_kortex repository for Gen3 ROS support!

Supported versions

The master branch has been tested with ROS Noetic.

For older ROS version, checkout on corresponding branch :

  • melodic-devel for ROS Melodic and Ubuntu 18.04 support.
  • kinetic-devel for ROS Kinetic and Ubuntu 16.04 support, but the branch is no longer maintained (the melodic-devel branch might work for this configuration).
  • indigo-devel for ROS Indigo and Ubuntu 14.04 support, but the branch is no longer maintained.

Kinova-ROS

The kinova-ros stack provides a ROS interface for the Kinova Robotics JACO, JACO2 and MICO robotic manipulator arms. Besides wide support of Kinova products, there are many bug fixes, improvements and new features as well. The stack is developed above the Kinova C++ API functions, which communicate with the DSP inside robot base.

Installation

To make kinova-ros part of your workspace, follow these steps (assuming your workspace is setup following the standard conventions):

cd ~/catkin_ws/src
git clone -b <branch-name> [email protected]:Kinovarobotics/kinova-ros.git kinova-ros
cd ~/catkin_ws
catkin_make

Another way to build your workspace would be to use the newer catkin build, which is part of the catkin_tools package:

# using apt-get
sudo apt-get install python-catkin-tools
# using pip
sudo pip install -U catkin_tools

Then, you add kinova-ros to your workspace and build it

cd ~/catkin_ws/src
git clone -b <branch-name> [email protected]:Kinovarobotics/kinova-ros.git kinova-ros
cd ~/catkin_ws
catkin build

More about the catkin_tools package in the official documentation

Note : To access the arm via usb copy the udev rule file 10-kinova-arm.rules from ~/catkin_ws/src/kinova-ros/kinova_driver/udev to /etc/udev/rules.d/:

sudo cp kinova_driver/udev/10-kinova-arm.rules /etc/udev/rules.d/

File System

  • kinova_bringup: launch file to start kinova_driver and apply some configurations.
  • kinova_control: files used by Gazebo.
  • kinova_demo: python scripts for actionlibs in joint space and cartesian space.
  • kinova_description: robot urdf models and meshes are stored here.
  • kinova_docs: kinova_comm reference html files generated by doxygen. The comments are based on the reference of Kinova C++ API, and some additional information is provided. The documents of Kinova C++ API are automatically installed while installing Kinova SDK from the Kinova website
  • kinova_driver: most essential files to run kinova-ros stack. Under the include folder, Kinova C++ API headers are defined in ../indlude/kinova, and ROS package header files are in kinova_driver folder. kinova_api source file is a wrap of Kinova C++ API, and kinova_comm builds up the fundamental functions. Some advanced accesses regarding to force/torque control are only provided in kinova_api. Most parameters and topics are created in kinova_arm. A general architecture from low level up could be: DSP --> communicate --> Kinova C++ API --> wrapped --> kinova_api --> kinova_comm --> {kinova_arm; kinova_fingers_action; kinova_joint_angles_action; ...} --> kinova_arm_driver. It is not recommended to modify kinova_comm and any level below it.
  • kinova_gazebo: ros package to launch a Gazebo simulation.
  • kinova_moveit: Everything related to Moveit! is stored here.
  • kinova_msgs: all the messages, servers and actionlib format are defined here.

How to use the stack

Launch driver

kinova_robot.launch in kinova_bringup folder launches the essential drivers and configurations for kinova robots. kinova_robot.launch has multiple arguments:

kinova_robotType specifies which robot type is used. For better supporting wider range of robot configurations, robot type is defined by a char[8], in the format of: [{j|m|r|c}{1|2}{s|n}{4|6|7}{s|a}{2|3}{0}{0}].

  • Robot category {j|m|r|c} refers to jaco, mico, roco and customized
  • version is {1|2} for now
  • wrist type {s|n} can be spherical or non-spherical
  • Degree of Freedom is possible to be {4|6|7}
  • robot mode {s|a} can be in service or assistive
  • robot hand {2|3} may equipped with 2 fingers or 3 fingers gripper.
  • The last two positions are undefined and reserved for further features.

eg: j2n6s300 (default value) refers to jaco v2 6DOF service 3 fingers. Please be aware that not all options are valided for different robot types.

To avoid redundancy urdf for assistive models has been deleted. Please use the service 's' option instead. For Mico 1 and 2 use the tag 'm1' for both. For Jaco 1 and 2 use the tag 'j2' for both.

kinova_robotName and kinova_robotSerial were added to allow multiple robots under a ros master. For applications like moveIt! set kinova_robotName to your prefix for the robot in the URDF. For example you can launch two jaco robots by using the following -

roslaunch kinova_bringup kinova_robot.launch kinova_robotType:=j2n6s300 kinova_robotName:=left kinova_robotSerial:=PJ00000001030703130
roslaunch kinova_bringup kinova_robot.launch kinova_robotType:=j2n6s300 kinova_robotName:=right kinova_robotSerial:=PJ00000001030703133

These parameters are optional and can be dropped off when only one robot is connected.

use_urdf specifies whether the kinematic solution is provided by the URDF model. This is recommended and is the default option.

When use_urdf:=true (default value), the kinematic solution is automatically solved by the URDF model. The robot can be virtually presented in Rviz and the frames in Rviz are located at each of the joints. To visulize the robot in Rviz, run $ rosrun rviz rviz, and select root as the world frame. The robot model will synchronize the motion with the real robot.

If use_urdf:=false, the kinematic solution is the same as the DSP code inside the robot. Node kinova_tf_updater will be activated to publish frames, and the frames are defined according the classic D-H convention(frame may not located at joints). Even you are not able to visualize the robot properly in Rviz, you would be able to observe the D-H frames in Rviz.

eg: roslaunch kinova_bringup kinova_robot.launch kinova_robotType:=j2n6s300 use_urdf:=true

If the robot is not able to move after boot, please try to home the arm by either pressing home button on the joystick or calling rosservice in the ROS service commands below.

rosservice call /'${kinova_robotType}'_driver/in/home_arm

Joint position control

Joint position control can be realized by calling KinovaComm::setJointAngles() in customized node, or you may simply call the node joints_action_client.py in the kinova_demo package. This function takes three parameters : kinova_robotType (eg. j2n6s300), unit {degree | radian} and value (angles for each joint). The function takes the option -r that will tell the robot if the angle values are relative or absolute. It also has the options -v for more verbose output and -h for help. The following code will drive the 6th joint of a 6DOF Jaco2 robot to rotate +10 degree (not to 10 degree), and print additional information about the joint position.

eg: rosrun kinova_demo joints_action_client.py -v -r j2n6s300 degree -- 0 0 0 0 0 10

Joint position can be observed by echoing two topics:

/'${kinova_robotType}_driver'/out/joint_angles (in degree) and

/'${kinova_robotType}_driver'/out/joint_state (in radians including finger information)

eg: rostopic echo -c /j2n6s300_driver/out/joint_state will print out joint names (rad), position, velocity (rad/s) and effort (Nm) information.

Another way to control joint position is to use interactive markers in Rviz. Please follow the steps below to active interactive control:

  1. launch the drivers: roslaunch kinova_bringup kinova_robot.launch kinova_robotType:=j2n6s300
  2. start the node of interactive conrol: rosrun kinova_driver kinova_interactive_control j2n6s300
  3. open Rviz: rosrun rviz rviz
  4. in RViz (in the display section) change Global Options -> Fixed Frame to world
  5. add robot's model with Add -> RobotModel (in rviz folder)
  6. add interactive markers with Add -> InteractiveMarkers (in rviz folder)
  7. change InteractiveMarkers -> Updated Topic to /j2n6s300_interactive_control_Cart/update
  • A ring should appear around each joint, you can move the robot by movings those rings.

Cartesian position control

Cartesian position control can be realized by calling KinovaComm::setCartesianPosition() in customized node. Alternatively, you may simply call the node pose_action_client.py in the kinova_demo package. This function takes three parameters : kinova_robotType (eg. j2n6s300), unit {mq | mdeg | mrad} (which refers to meter&Quaternion, meter&degree and meter&radian) and pose_value. The last argument, pose_value, is the position (in coordonates x,y,z) followed by the orientation (either 3 or 4 values based on unit). The unit of position is always meter, and the unit of orientation is different. Degree and radian are in relation to Euler Angles in XYZ order. Please be aware that the length of parameters are different when using Quaternion and Euler Angles. The function takes the option -r that will tell the robot if the angle values are relative or absolute. It also has the options -v for more verbose output and -h for help. The following code will drive a Jaco2 robot to move along +x axis for 1cm and rotate the hand for +10 degree along hand axis.

eg: rosrun kinova_demo pose_action_client.py -v -r j2n6s300 mdeg -- 0.01 0 0 0 0 10

The Cartesian coordinate of robot root frame is defined by the following rules:

  • origin is the intersection point of the bottom plane of the base and cylinder center line.
  • +x axis is directing to the left when facing the base panel (where power switch and cable socket locate).
  • +y axis is towards to user when facing the base panel.
  • +z axis is upwards when robot is standing on a flat surface.

The kinova_tool_pose_action (action server called by pose_action_client.py) will send Cartesian position commands to the robot and the inverse kinematics will be handled within the robot. Important The inverse kinematics algorithm that is implemented within Kinova robots is programmed to automatically avoid singularities and self-collisions. To perform those avoidance, the algorithm will restrict access to some parts of the robot's workspace. It may happen that the Cartesian pose goal you send cannot be reached by the robot, although it belongs to the robot's workspace. For more details on why this can happen, and what can you do to avoid this situation, please see the Q & A in issue #149. As a rule of thumb, if you are not able to reach the pose you are commanding in pose_action_client.py by moving your Kinova robot with the Kinova joystick, the robot will not be able to reach this same pose with the action server either. If you do not want to use the robot's IK solver, you can always use MoveIt instead.

The current Cartesian position is published via topic: /'${kinova_robotType}_driver'/out/tool_pose

In addition, the wrench of end-effector is published via topic: /'${kinova_robotType}_driver'/out/tool_wrench

Again, you can also use interactive markers in Rviz for Cartesian position :

  1. launch the drivers: roslaunch kinova_bringup kinova_robot.launch kinova_robotType:=j2n6s300
  2. start the node of interactive conrol: rosrun kinova_driver kinova_interactive_control j2n6s300
  3. open Rviz: rosrun rviz rviz
  4. in RViz (in the display section) change Global Options -> Fixed Frame to world
  5. add robot's model with Add -> RobotModel (in rviz folder)
  6. add interactive markers with Add -> InteractiveMarkers (in rviz folder)
  7. change InteractiveMarkers -> Updated Topic to /j2n6s300_interactive_control_Cart/update
  • A cubic with 3 axis (translation) and 3 rings(rotation) should appear at the end-effector, you can move the robot by dragging the axis or rings.

New in release 1.2.0

Executing multiple Cartesian waypoints without stopping
The action client executes one goal at a time. In case the user wants to give multiple waypoints to the robot without stopping at every waypoint, the service AddPoseToCartesianTrajectories can be used. This service adds the commanded poses to a buffer that that maintained by the robot. The robot executes the poses in this buffer in the order that they are added, without stopping between poses.

The service ClearTrajectories can be used to clear the trajectory buffer in the base.

Finger position control

Cartesian position control can be realized by calling KinovaComm::setFingerPositions() in customized node. Alternatively, you may simply call the node fingers_action_client.py in the kinova_demo package. This function takes three parameters : kinova_robotType (eg. j2n6s300), unit {turn | mm | percent} and finger_value. The finger is essentially controlled by turn, and the rest units are propotional to turn for convenience. The value 0 indicates fully open, while finger_maxTurn represents fully closed. The value of finger_maxTurn may vary due to many factors. A proper reference value for a finger turn will be 0 (fully-open) to 6800 (fully-close). If necessary, please modify this variable in the code. The function also takes the option -r that will tell the robot if the angle values are relative or absolute. It also has the options -v for more verbose output and -h for help. The following code fully closes the fingers.

eg: rosrun kinova_demo fingers_action_client.py j2n6s300 percent -- 100 100 100

The finger position is published via topic: /'${kinova_robotType}_driver'/out/finger_position

Velocity Control for joint space and Cartesian space

The user has access to both joint velocity and Cartesian velocity (angular velocity and linear velocity). The joint velocity control can be realized by publishing to topic /'${kinova_robotType}_driver'/in/joint_velocity. The following command can move the 6th joint of a Jaco robot at a rate of approximate 10 degree/second. Please be aware that the publishing rate does affect the speed of motion.

eg: rostopic pub -r 100 /j2n6s300_driver/in/joint_velocity kinova_msgs/JointVelocity "{joint1: 0.0, joint2: 0.0, joint3: 0.0, joint4: 0.0, joint5: 0.0, joint6: 10.0}"

For Cartesian linear velocity, the unit is meter/second. Definition of angular velocity "Omega" is based on the skew-symmetric matrices "S = R*R^(-1)", where "R" is the rotation matrix. angular velocity vector "Omega = [S(3,2); S(1,3); S(2,1)]". The unit is radian/second. An example is given below:

eg: rostopic pub -r 100 /j2n6s300_driver/in/cartesian_velocity kinova_msgs/PoseVelocity "{twist_linear_x: 0.0, twist_linear_y: 0.0, twist_linear_z: 0.0, twist_angular_x: 0.0, twist_angular_y: 0.0, twist_angular_z: 10.0}"

The motion will stop once the publish on the topic is finished. Please be cautious when using velocity control as it is a continuous motion unless you stop it.

Note on publish frequency : The joint velocity is set to publish at a frequency of 100Hz, due to the DSP inside the robot which loops each 10ms. Higher frequency will not have any influence on the speed. However, it will fill up a buffer (size of 2000) and the robot may continue to move a bit even after it stops receiving velocity topics. For a frequency lower than 100Hz, the robot will not able to achieve the requested velocity.

Therefore, the publishing rate at 100Hz is not an optional argument, but a requirement.

ROS service commands

Users can home the robot with the command below. It takes no argument and brings the robot to pre-defined home position. The command supports customized home position that users can define by using the SDK or JacoSoft as well. rosservice call /'${kinova_robotType}_driver'/in/home_arm

Users can also enable and disable the ROS motion commands with these rosservices : rosservice call /'${kinova_robotType}_driver'/in/start /'${kinova_robotType}_driver'/in/stop When stop is called, robot commands from ROS will not drive the robot until start is called. However, the joystick still has the control during this phase.

Cartesian Admittance mode

This lets the user control the robot by manually (by hand). The admittance force control can be actived and deactivated with these commands :

rosservice call /'${kinova_robotType}_driver'/in/start_force_control
rosservice call /'${kinova_robotType}_driver'/in/stop_force_control

The user can move the robot by applying force/torque to the end-effector/joints. When there is a Cartesian/joint position command, the result motion will be a combination of both force and position commands.

Re-calibrate torque sensors

New in release 1.2.0

Over time it is possible that the torque sensors develop offsets in reporting absolute torque. For this they need to be re-calibrated. The calibration process is very simple -

  1. Move the robot to candle like pose (all joints 180 deg, robot links points straight up). This configuration ensures zero torques at joints.
  2. Call the service rosservice call /'${kinova_robotType}_driver'/in/set_zero_torques

Support for 7 dof spherical wrist robot

New in release 1.2.0

Support for the 7 dof robot has been added in this new release. All of the previous control methods can be used on a 7 dof Kinova robot.

Inverse Kinematics for 7 dof robot

The inverse kinematics of the 7 dof robot results in infinite possible solutions for a give pose command. The choice of the best solution (redundancy resolution) is done in the base of the robot considering criteria such as joint limits, closeness to singularities.

Move robot in Null space

To see the full set of solutions, a new fuction is introduced in KinovaAPI - StartRedundantJointNullSpaceMotion(). When in this mode the Kinova joystick can be used to move the robot in null space while keeping the end-effector maintaining its pose.

The mode can be activated by calling the service SetNullSpaceModeState - ${kinova_robotType}_driver /in/set_null_space_mode_state Pass 1 to service to enable and 0 to disable.

Torque control

New in release 1.2.0

Torque control has been made more accessible. Now you can publish torque/force commands just like joint/cartesian velocity. To do this you need to :

  1. Optional - Set torque parameters
    Usually default parameters should work for most applications. But if you need to change some torque parameters, you can set parameters (listed at the end of page) and then call the service -
    SetTorqueControlParameters ${kinova_robotType}_driver/in/set_torque_control_parameters

  2. Switch to torque control from position control
    You can do this using the service - SetTorqueControlMode ${kinova_robotType}_driver'/in/set_torque_control_mode

  3. Publish torque commands rostopic pub -r 100 /j2n6s300_driver/in/joint_torque kinova_msgs/JointTorque "{joint1: 0.0, joint2: 0.0, joint3: 0.0, joint4: 0.0, joint5: 0.0, joint6: 1.0}"

Gravity compensation

Gravity compensation is done by default in the robot's base. This means that if the robot is commanded zero torques the robot does not fall under gravity. This case (zero commanded torque) can be refered to as gravity compensated mode. The robot can be moved around freely by manually pushing its joints. You can try out this mode by using the command (for a j2n6s300)

rosrun kinova_demo gravity_compensated_mode.py j2n6s300 

This command moves the robot to a candle-like pose, sets torques to zero, and then starts torque control mode. It publishes torque commands as [0,0,0,0,0,0], so the robot can be moved by pushing on individual joints.

It is posible to publish torque with or without gravity compensation by setting the parameter -

publish_torque_with_gravity_compensation: false
Torque inactivity

If not torque command is sent after a given time (250ms by default), the controller will take an action: (0): The robot will return in position mode (1): The torque commands will be set to zero. By default, option (1) is set for Kinova classic robots (Jaco2 and Mico) while option (0) is set for generic mode.

Ethernet connection

New in release 1.2.0

Note - Although this release supports Ethernet connection, this feature is limited. Kinova will notify all users when Ethernet support is released for all customers.

Support for Ethernet connection has been added. All functionalities available in USB are available in Ethernet. To use ethernet follow these steps

  1. Setup a static IP address for your ethernet network say - 192.168.100.100
  2. With the robot connected to your PC via USB open kinova's Develepment Center
  3. Open tab General/Ethernet - Set robot IP Address to something like - 192.168.100.xxx
  4. Make sure MAC address is not all zero. If so contact [email protected]
  5. Press 'Update' and restart robot
  6. In a terminal ping your robot's IP, your robot is setup for ethernet

To connect to robot via ethernet in ROS just set these parameters in robot_parameters.yaml -

connection_type: Ethernet  
local_machine_IP: [your PC network IP]  
subnet_mask: [your network subnet mask]  

Parameters

New in release 1.2.0

General parameters
  • serial_number: PJ00000001030703130 Leave commented out if you want to control the first robot found connected.
  • jointSpeedLimitParameter1: 10 Joint speed limit for joints 1, 2, 3 in deg/s
  • jointSpeedLimitParameter2: 20 Joint speed limit for joints 4, 5, 6 in deg/s
  • payload: [0, 0, 0, 0] payload: [COM COMx COMy COMz] in [kg m m m]
  • connection_type: USB Ethernet or USB
Ethernet connection parameters
ethernet: {
	local_machine_IP: 192.168.100.100,  
	subnet_mask: 255.255.255.0,  
	local_cmd_port: 25000,  
	local_broadcast_port: 25025  
}
Torque control parameters

Comment these out to use default values.

torque_parameters:

  • publish_torque_with_gravity_compensation: false
  • torque_min: [1, 0, 0, 0, 0, 0, 0]
  • torque_max: [50, 0, 0, 0, 0, 0, 0]
    If one torque min/max value is sepecified, all min/max values need to be specified
  • safety_factor: 1
    Decides velocity threshold at which robot switches torque to position control (between 0 and 1)
  • com_parameters: [0,0,0,0,0,0,0, 0,0,0,0,0,0,0, 0,0,0,0,0,0,0, 0,0,0,0,0,0,0] COM parameters, order [m1,m2,...,m7,x1,x2,...,x7,y1,y2,...y7,z1,z2,...z7]

rqt GUI for robot status

ROS provides a flexible GUI tool to interact with nodes/robots - rqt. You can use this tool to see topics published by the node - robot position, velocity, torque, etc. You can also launch services like AddPoseToCartesianTrajectory.

Monitoring topics

  • Launch rqt by typing the command rqt
  • In the plugin tab, select Topics/Topics monitor
  • Select any messages to see published position/torque etc. values

Other plugins in rqt can similarly be used for quick interation with the robot.

Gazebo

More informations about Gazebo available here

MoveIt!

More informations about MoveIt! available here

New in this release

New in release 1.2.1

A few bug fixes:

Specific to 7 dof robot:

  • PID controller parameters for the 7 dof robot with spherical wrist (before, the Gazebo model was unstable when launched)
  • addition of an is7dof argument in kinova_gazebo/launch/robot_launch.launch and kinova_control/launch/kinova_control.launch to load joint_7_position_controller in addition to other position_controllers when launching the gazebo model with use_trajectory_controller set to false and a 7 dof robot. This argument has to be set to true for a 7 dof robot.
  • correction in kinova_control/launch/j2s7s300.perspective (rqt tool was publishing to wrong topic)

Specific to MICO robot:

  • correction in kinova_control/launch/m1n6s200.perspective (rqt tool was publishing to wrong topic)

For all robots:

  • fix in home_arm service (before, was not working when robot was connected through Ethernet)
  • commented out the COM parameters all set to zero in kinova_bringup/launch/config/robot_parameters.yaml, or else the robot does not compensate gravity accurately when switched to admittance or torque mode. These COM parameters can be commented out if the user wants to change the default COM parameters, but by default, we take for granted that the user wants to use the parameters already implemented in the robot.
  • change the order conditions are checked in the kinova_joint_angles_action.cpp, kinova_tool_pose_action.cpp and kinova_fingers_action.cpp to ensure that the robot does not accept new goals after having been stopped (emergency stop). See issue #92 for more details.

New in release 1.2.0

  • Gazebo support
  • MoveIt! support
  • Restructured URDF files
  • Support for 7 dof robot
  • Support for Ethernet
  • Torque control through publisher/subscriber
  • Force control through publisher/subscriber
  • Torque control parameters
  • Speed limit for actionlib Cartesian/Joint control
  • Parameterized base_frame for tf_generator
  • Finger models are now updated in RViz
  • Ring models added to URDF
  • New demo file - gravity_compensated_mode.py
  • Test/demo file - TestSrv.py
  • New services
    • SetTorqueControlParameters
    • SetZerotorque
    • SetNullSpaceModeState
    • AddPoseToCartesianTrajectory
    • ClearTrajectories
    • SetTorqueControlMode

Notes and Limitations

  1. Force/torque control is only for advanced users. Please use caution when using force/torque control api functions.

  2. The joint_state topic currently reports the joint Names, Position,Velocity and Effort. Depending on your firmware version velocity values can be wrong.

  3. When updating the firmware on the arm (e.g., using Development Center) the serial number will be set to "Not set" which will cause multiple arms to be unusable. The solution is to make sure that the serial number is reset after updating the arm firmware.

  4. Some virtualization software products are known to work well with this package, while others do not. The issue appears to be related to proper handover of access to the USB port to the API. Parallels and VMWare are able to do this properly, while VirtualBox causes the API to fail with a "1015" error.

  5. Previously, files under kinova-ros/kinova_driver/lib/i386-linux-gnu had a bug which required users on 32-bit systems to manually copy them into devel or install to work. This package has not been tested with 32-bit systems and this workaround may still be required. 64-bit versions seem to be unaffected.

Report a Bug

Any bugs, issues or suggestions may be sent to [email protected]

kinova-ros's People

Contributors

abencz avatar alexvannobel avatar andrejorsula avatar aruisdante avatar bpwiselybabu avatar christian-rauch avatar cyrilanderson avatar dniewinski avatar felixmaisonneuve avatar ferrolho avatar francoisferland avatar hommeabeil avatar j-rivero avatar jeff-o avatar jpcotekinova avatar k-okada avatar kinova avatar martine1406 avatar mpmendes avatar nsaif-kinova avatar oars avatar pliniomoreno avatar quartzyan avatar samuelhovington avatar sbrisebois avatar simonferronforget avatar soli7 avatar szutshi620 avatar tf-maam avatar yowlings avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

kinova-ros's Issues

Error Code 1015

When attempting to run the node from inside the virtual machine I get error code 1015. Although I see that the error is ERROR_CLAIM_INTERFACE, I am unsure what that means and what is causing it.

Please advise.

Drinking Mode Enabled (default)

Hello,

We are using the mico arm with the kinova api. When we send Cartesian velocity using the SendAdvancedTrajectory call the robot acts in the drinking mode (a velocity in +Y direction makes the arm wrist to rotate and it will go near the drinking position). The ActualSystemStatus for the DrinkingMode is 0 (enabled by default). We do not have a Kinova joystick.
How can we disable the DrinkingMode and achieve a normal Cartesian behavior for the velocity control using the api?

Thanks!

Siddarth

Jaco drivers don't work with the gripper alone

I have a KG-3 gripper with me, which I would like to connect to ta different robot and I would like to use the jaco ros to connect to the gripper.
I have the base power supply module and I am connecting to it using USB and every time I try to launch the jaco_arm.launch I get the following error

[ INFO] [1449704319.866393727]: Initializing Kinova API (header version: 50101, library version: 5.0.6)
[ERROR] [1449704319.868765466]: JacoCommException: Could not initialize Kinova API (return code: 1015)

I assume that the drivers are failing to connect as it is not able to communicate with the firmware in the arm.
It would be really helpful if there was a way to use the gripper without the Jaco ARM.

Nice message when homing the arm

I get a nice output when I home the arm:
[ INFO] [1476979654.727292332]: haha Arm is in "home" position

You might want to correct line 1208 of kinova_driver/src/kinova_comm.cpp

Cheers :)

Documentation misleading

Throughout the README.md it says the parameter is node_name such as:

rosrun jaco_demo joint_angle_workout.py node_name random num        - randomly generate num joint angle sets

This is misleading because when running rosnode list I see my node is called "jaco_arm_driver" but what these python scripts actually want is just "jaco". I think the scripts should be changed to use the whole node name so it is more intuitive to ROS users.

jaco_comm::setFingerPositions fails on the Mico arm in some poses

In some end effector poses, the setFingerPositions command does not cause the fingers to move.
This is reproducible by putting the mico arm in the position:

Actuators:
Actuator1: 241.93
Actuator2: 281.801
Actuator3: 161.085
Actuator4: 240.205
Actuator5: 68.1818
Actuator6: 104.386

and then calling the setFingersPosition with the values 4000,4000, 4000.

The exact resulting TajectoryPoint sent can be found here:
https://gist.github.com/jon-weisz/e6baf40ea9cd7711e613

Sending the same command in Angular Position mode results in the fingers closing, but the hand dropping slightly, as described in the known issues occuring with the Jaco arm.

The drop appears to be on the order of .005 m, which is problematic for fingertip grasping.

Jaco arm moves once

I started to work with jaco_driver, I encounter a problem which is as follows:

I launch the "jaco_driver" and run "pose_action_client.py". The arm moves to the defined position. but if I want to try to send a new goal by rerunning the script and change the position, the arm does not move.

More interestingly, If I kill the launch and the script and repeat everything from scratch (even turn off the arm and then turn it on), the arm does "NOT" move. It will work again only if I restart the computer!

Do you have any suggestion what would be the problem?

Parameterize root link

I noticed here

broadcaster_.sendTransform(tf::StampedTransform(transform, ros::Time::now(),
                                            "root",
                                            concatTfName(tf_prefix_, "link_base")));

That the base tf is hard coded to "root". It would be useful to be able to define that as a parameter. In my case, the reason is that the arm is mounted onto other stuff therefore the base link of the arm isn't "root".

Only two fingers "home" on JACO; cannot be controlled until homed manually

When using the home_arm service, the JACO2 successfully homes along with just two of its fingers. The third finger does not move, and as a result the third finger does not respond to movement commands (in this case, grip_workout.py was used to test the fingers). The joystick controller must be used to manually move the fingers to the fully open position, at which point the API is able to control all three of the fingers.

mico_arm.launch cannot find my mico arm

Hi, I'm working with a mico arm (firmware: Actuators 1.2.6, Fingers 1.1.3) on the Ubuntu 12.04 ros hydro.

When I roslaunch the mico_arm.launch (or jaco_arm.launch), the terminal display these messages as follows:

[ INFO] [1411619270.995993976]: Initializing Kinova API (header version: 50101, library version: 5.0.6)
[ERROR] [1411619271.106618061]: Could not find the specified arm (serial: PJ00650002132770005) among the 1 attached devices
[ERROR] [1411619271.106820590]: JacoCommException: Could not find the specified arm (return code: 0)

However, the arm.launch can initialize the API successfully.

Add simplified collision and inertial elements to the URDF model.

Kinova should provide a simplified collision model for e.g. collision checking or robot body removal from point clouds. Please, try to provide the model in terms of primitive shapes, not meshes (which are slow in computations). Or at least provide simplified convex hulls of the meshes.

As a starting point, you can cherry-pick my work for Jaco arm: 14c006a (I won't create a PR because we have lots of different stuff changed in our working branch).

Make Error

During catkin_make an error in kinova_comm.cpp occurs due to the header file:

include <KinovaTypes.h>

I guess Changing it into:

include "KinovaTypes.h" solves the problem for me.

32-bit architectures not fully supported

The 32 bit CommandLayer API for Jaco expects to find the comm library in the directory which the Jaco node is launched from. This is unlike the 64 bit version of the API which will look in system library paths. As a result, on 32-bit architectures, the node will fail to launch as-is since roslaunch launches everything from ROS_HOME.

As a workaround, the comm library may be copied to the ROS_HOME, e.g.:

$ roscd jaco_driver/lib/i386-linux-gnu
$ cp Kinova.API.CommLayerUbuntu.so ~/.ros/

This should fix launching the node with roslaunch or rosrun.

Cartesian Velocity and Position Control not Working

We are using the mico arm with 6 joints and two fingers and firmware version 5.2.1.22 using the latest kinova-ros driver. The joint position and velocity control is working fine, however the cartesian position and control is not working. Also, mico_home service is not working. We were using the command line tools as mentioned in the readme.

We tested the kinova SDK (in Windows) and we were able to control the cartesian velocity using the keyboard. However this only works once the robot is sent to home position using -H on the keyboard.

Do you have any ideas on how we can debug this issue?

Jaco Arm not being detected even though it's connected

Whenever I run "roslaunch jaco_driver jaco_arm_launch" I get the following error -

[ INFO] [1438286522.917873264]: Initializing Kinova API (header version: 50101, library version: 5.0.6)
[ERROR] [1438286523.031603216]: JacoCommException: Could not get general information about the device (return code: 2005)

The arm was working properly before this, so I am unsure what exactly went wrong.

Error Code 1014

I'm receiving error code 1014 (ERROR_JACO_CONNECTION) when I try to run the launch file jaco_driver/launch/jaco_arm.launch. I get the following error output:

[FATAL] [1381469449.501827749]: Could not initialize arm
[FATAL] [1381469449.502122084]: Jaco_InitAPI returned: 1014
[jaco/jaco_arm_driver-2] process has died [pid 12775, exit code -11, cmd /home/lukegt/fuerte_workspace/ros-jaco-arm/jaco_driver/bin/jaco_arm_driver __name:=jaco_arm_driver __log:=/home/lukegt/.ros/log/483080d2-3236-11e3-8d47-000c29e2478c/jaco-jaco_arm_driver-2.log].
log file: /home/lukegt/.ros/log/483080d2-3236-11e3-8d47-000c29e2478c/jaco-jaco_arm_driver-2*.log

Thinking that it might've been a permissions issue, I created the following file: /etc/udev/rules.d/50-kinova.rules

# libusb Jaco nodes
SUBSYSTEM=="usb", ENV{DEVTYPE}=="usb_device",ATTRS{idVendor}=="22cd", MODE="0666"

But this didn't work out. lsusb gives the following output, with the last entry being what I believe to be the Jaco arm:

Bus 002 Device 002: ID 0e0f:0003 VMware, Inc. Virtual Mouse
Bus 002 Device 003: ID 0e0f:0002 VMware, Inc. Virtual USB Hub
Bus 001 Device 001: ID 1d6b:0002 Linux Foundation 2.0 root hub
Bus 002 Device 001: ID 1d6b:0001 Linux Foundation 1.1 root hub
Bus 002 Device 027: ID 22cd:0000  

I'm running 32-bit Ubuntu 12.04 in a VM Workstation virtual machine. My host OS is Windows, and I can successfully connect to the Jaco using Jacosoft.

Any clues as to what's going on here? Any guidance will be much appreciated.

JACO version 1 URDF model missing?

I need to write code that works with both JACO and JACO2, however when I tried to launch with kinova_robotType:=j1n6a300 I get an error message that the file 'j1n6a300_standalone.xacro' does not exist. I looked in the folder, and there are no URDF files for JACO version 1?

How can the new API be used with both versions of the arm - with URDF model?

'Failed to contact arm' Notification

I'm just started to work with a JACO arm, using the 'catkin'. In my first tries of using the driver an error was reported ([jaco/jaco_arm_driver-1] process has died [pid 6739, exit code -11...), searching on the file 'jaco_comm.cpp' I realized that was because the arm wasn't turned on, but the error message doesn't say that.
The code that shows the real error (lines 81 - 93) is not even executed, my suggestion is to change the position of this part of code to before the 'StartControlAPI' call.
Here this change works very well.

Unable to use /arm_pose/goal to move arm

Trying to move the arm by publishing directly to the topic as:

rostopic pub --once /arm_pose/goal jaco_driver/ArmPoseActionGoal "{header: auto, goal_id:{'id':""}, goal:{pose:{pose:{position:[0.20, -0.23, 0.43], orientation:[0, 0, 0, 1]}}}}

results in the following error:

[ INFO] [1377780222.922908564]: Got a cartesian goal for the arm
[ERROR] [1377780222.923070135]: Could not get transfrom from /jaco_api_origin to , aborting cartesian movement
[ WARN] [1377780222.923222014]: Your executeCallback did not set the goal to a terminal status.
This is a bug in your ActionServer implementation. Fix your code!
For now, the ActionServer will set this goal to aborted

How to follow joint trajectory with a continuous path

When I use the joint_angle_workout.py demo to execute an ArmJointAnglesAction (send a series of trajectory points to the robot arm), the arm can follow the joint trajectory well, but it stops at each waypoint before driving to the next waypoint. Is it posiible to drive through the desired path faster without stopping at each waypoint? Thanks a lot!

Missing links in URDF description of MICO arm

I was playing a little bit with the URDF model of the Mico arm in rviz,
and I realized that the fingers do not have the additional underactuated
joint. Are you planning on releasing soon the full gripper URDF model?

ROS release?

Are you going to release the new library as an official ROS package?

Force Control not appearing for Mico arm

When I connect to the arm get everything running I try the command:

 rosservice call /jaco_arm_driver/in/start_force_control

and then get the error:

 Error: Service [/jaco_arm_driver/in/start_force_control] is not available.

And when I check if it exists with:

 rosservice list

it is not on the list.

Furthermore, at the top of the documentation on your main page, it does not list Force Control as a service provided but it does further down the page in the services section.

So my question is, is Force Control possible with the Mico Arm?
And can the main page be updated so as to not have the confusion?

Thank you for any help!

j2n6a300_state_publisher publishing to the wrong namespace?

I've embedded "kinova_bringup/launch/kinova_robot.launch" in a namespace (e.g. "kinova_ns"), which leads to that almost all topics has the correct prefix. The exception is the topic "/j2n6a300_driver/out/joint_state" (subscribed to by "j2n6a300_state_publisher").

I don't think this causes troubles, but it does not look as nice.

Issues with joints_action_client code - decrease velocity, joystick switches to joint space control?

I use part of the joints_action_client to move the arm to certain configurations, but have some troubles:

  • For what I am testing the joint velocity is a bit too high for having time to manually counter potential collisions, is it possible to set a lower velocity?
  • After setting a joint configuration the joystick controls the arm in joint-space instead of cartesian space. Is this a known problem? Is there a fix?
  • Is there some way to take (known) obstacles into account when moving to pre-defined joint configurations?

KinovaCommException: Could not initialize Kinova API (return code: 1015)

Hi,

I am trying to launch the package, so, I typed $roslaunch kinova_bringup kinova_robot.launch
then got an error and it stuck there,

[ INFO] [1474363787.379153676]: Initializing Kinova API (header version: 50200, library version: 5.2.0)
[ERROR] [1474363787.381342213]: KinovaCommException: Could not initialize Kinova API (return code: 1015)

I found something about 1015 at the bottom of Readme but It does not give me any help.

How can I solve this? :(

Env is
Ubuntu 16.04 (not VM) with ROS Kinetic 1.12.2

  • It happened on Ubuntu 14.04 with ROS Indigo, Ubuntu 12.04 with ROS Fuerte / Hydro as well.
  • I just found another thing,
    If I try to launch with robot type m2, (e.g. m2n6s300, m2n4a200, whatever.) then an error occurs.
    full terminal log below.

$ roslaunch kinova_bringup kinova_robot.launch kinova_robotType:=m2n4a300
... logging to /home/drivebot/.ros/log/73ca7f8c-7f1c-11e6-9d79-fcaa14a2287a/roslaunch-drivebot-M4HM85P-00-20749.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: Traditional processing is deprecated. Switch to --inorder processing!
To check for compatibility of your document, use option --check-order.
For more infos, see http://wiki.ros.org/xacro#Processing_Order
No such file or directory: /home/drivebot/catkin_ws/src/kinova-ros/kinova_description/urdf/m2n4a300_standalone.xacro
XacroException('No such file or directory: /home/drivebot/catkin_ws/src/kinova-ros/kinova_description/urdf/m2n4a300_standalone.xacro',)
Invalid tag: Cannot load command parameter [robot_description]: command [/opt/ros/kinetic/share/xacro/xacro.py '/home/drivebot/catkin_ws/src/kinova-ros/kinova_description/urdf/m2n4a300_standalone.xacro'] returned with code [2].

Param xml is <\param command="$(find xacro)/xacro.py '$(find kinova_description)/urdf/$(arg kinova_robotType)_standalone.xacro'" name="robot_description"/>
The traceback for the exception was written to the log file

Regards, Sun

Catkin Build

It would be nice to have support for Catkin to use the node within the Groovy build system.

J5 on the mico appears to be offset by 1/2 PI

I am trying to write nodes that consume the state of the mico arm. I know that some (all?) of the joints on the MICO are continuous. This wouldn't be a problem if they all wrapped between -PI and +PI, but I have noticed that joint 6 (index 5) appears to be wrapping between -1/2 PI and + 3/2 PI. Is this the desired behavior? If so, I have to write special cases anywhere J5 is used in my code.

It basically comes down to these lines in the arm driver:

    double j6o = jaco_comm_.robotType() == 2 ? 270.0 : 260.0;
    joint_state.position[0] = (180- jaco_angles.joint1) * (PI / 180);
    joint_state.position[1] = (jaco_angles.joint2 - j6o) * (PI / 180);
    joint_state.position[2] = (90-jaco_angles.joint3) * (PI / 180);
    joint_state.position[3] = (180-jaco_angles.joint4) * (PI / 180);
    joint_state.position[4] = (180-jaco_angles.joint5) * (PI / 180);
    joint_state.position[5] = (270-jaco_angles.joint6) * (PI / 180);

Where position[5] for some reason is offset by 270 degrees (1.5 PI), wheras the value wraps between -pi and +pi.

Start/Stop of API control doesn't work with firmware version 5.0.5.33

On firmware version 4.x I was able to stop the API control by just moving the joystick or pressing a button. On the latest version, nothing happens and even if I stop the API control programmatically it doesn't work. It also seems that the led indicators on the Joystick have changed. When in API mode led one and two was lit on the older firmware, when not in API control only led one was on. Now in the new firmware when not in API control only led one is on and if not in API control no led is on.
I would really be able to stop API control because it's the only save method to stop the Jaco.

Gazebo Compatibility

Are there plans to add the capability to simulate Jaco / Mico kinematics in Gazebo? Would be a nice feature to have to test functionality while awaiting delivery of arm.

[Question] Mico arm maximum rate [hz]?

Hi,

I would like to remotely control the mico arm with a master device (like a joystick). What is the maximum refresh rate of the Mico arm?

And how can I change it?

Thanks.

Jaco fails to hold joint angles when fingers are controlled

Hello,
I am using Jaco arm for pick and place task using 3 finger gripper.
My code is in ROS. I set the noint angles first using jaco_angle_action server, then try to control finger positions using jaco_fingers_action server.
These two action servers are sent the goals in same python node. Finger positions are changed by the client periodically in a while loop.
I observe that, both of the tasks, that are, moving the fingers and holding up the arm position fail to happan simultaneously.
The arm is seen to be moving under the influence of gravity when fingers are being controlled.
The arm keeps going down in jerks, finally ends up on the floor.

Any pointers on how to work it around are most appreciated.
Also a quick response would be highly useful as publishing a paper with approaching deadline is blocked by this issue.

Thanking in advance,
Kunal

Symbol lookup errors

We have a MICO research edition arm and are trying to get it to work. When we use the jaco_arm_driver from here we can built it (although we had to add ${CMAKE_DL_LIBS} to the target_link_libraries of the jaco_arm_driver). When we try to run it we get:

./jaco_arm_driver: symbol lookup error: /home/x/catkin_ws/devel/lib/libjaco_pose.so: undefined symbol: _ZN2tf11Transformer18DEFAULT_CACHE_TIMEE

and:

./jaco_tf_updater: symbol lookup error: home/x/catkin_ws/devel/lib/libjacokinematics.so: undefined symbol: _ZN2tf20TransformBroadcasterC1Ev

It seems that certain libraries cannot be found (as symbol lookup error suggests). How can we fix this problem? We are using Ubuntu 12.04.

Which joints are continuous?

From the README.md, it seems like only the last 3 wrist joints are continuous. But in the URDF here it also makes joint 1 continuous:

<xacro:jaco_joint joint_name="${joint_1}" type="continuous" parent="${link_base}" child="${link_1}" joint_axis_xyz="${joint_1_axis_xyz}" joint_origin_xyz="${joint_1_origin_xyz}" joint_origin_rpy="${joint_1_origin_rpy}" joint_lower_limit="${joint_1_lower_limit}" joint_upper_limit="${joint_1_upper_limit}"/>

Is this a bug?

I'm using Jaco 2, is there a difference?

Also, are there reasons to set fake limits? I see the comment in the README.md:

You may want to limit to +/-6.28 rad in software to prevent the joints from rotating excessively.

Cartesian_workout doesn't work

I can subscribe to cartesian topics like tool_position but the cartesian workout just doesn't work. On the terminal it says Using the specified pose and Done but nothing happens to the real arm.

Everything else has worked perfectly so far except for this cartesian_workout.

Any hints on this one?

[Question] What is the correct transformation matrices of MICO?

Hello,

I need the transformation matrices of MICO to control it.
Now I'm using the matrices referring to the comments on jaco_arm_kinematics.cpp.
However, tfs from jaco_tf_updater.cpp (which uses jaco_arm_kinematics.cpp, you may know) is different from tfs from MICO's urdf.

Which is the same as the real MICO configulations?
How can I know the transformation matrices of MICO?

thanks.

roslaunch kinova_bringup fails

I tried to launch robot with following command :
roslaunch kinova_bringup kinova_robot.launch kinova_robotType:=j2s7s300 use_urdf:=false
but it returns error :
[ INFO] [1469825146.149697563]: kinova_robotType is j2s7s300.
Please specify the kinematic of robots other than jaco and mico!
[j2s7s300_driver-1] process has died [pid 2725, exit code -6, cmd /home/administrator/vinobot_ws/devel/lib/kinova_driver/kinova_arm_driver j2s7s300 __name:=j2s7s300_driver __log:=/home/administrator/.ros/log/694e5d8c-55cb-11e6-bc33-003018c2a7c0/j2s7s300_driver-1.log].
log file: /home/administrator/.ros/log/694e5d8c-55cb-11e6-bc33-003018c2a7c0/j2s7s300_driver-1*.log

Code review of fferland-newapi

I know this branch isn't ready, but I need my Jaco 2 working now so I studied your changes. If you don't mind:

There is a misspelling of "RefresDevicesList" in include/kinova/Kinova.API.UsbCommandLayerUbuntu.h

In kinova_driver/src/jaco_arm.cpp there appears to be a regression where it says

joint_state.position[1] = (jaco_angles.joint2 - 270) * (PI / 180);

shouldn't the 270 be the variable j6o like it was previously?

Also, how stable is this and the experimental branch? How many bumps should I expect if I start using it now?

Could not find the specified arm among the 1 attached devices

Trying to control Jaco arm with ROS-hydro and jaco-ros

the arm appears to be connected using 'lsusb'
Bus 001 Device 002: ID 13d3:5702 IMC Networks UVC VGA Webcam
Bus 002 Device 015: ID 22cd:0000
Bus 001 Device 001: ID 1d6b:0002 Linux Foundation 2.0 root hub
Bus 002 Device 001: ID 1d6b:0001 Linux Foundation 1.1 root hub
Bus 003 Device 001: ID 1d6b:0001 Linux Foundation 1.1 root hub
Bus 004 Device 001: ID 1d6b:0001 Linux Foundation 1.1 root hub
Bus 005 Device 001: ID 1d6b:0001 Linux Foundation 1.1 root hub

This is what i get when I do roslaunch jaco_driver jaco_arm.launch

[ INFO] [1415117300.461576789]: Initializing Kinova API (header version: 50101, library version: 5.0.6)
[ERROR] [1415117300.684649220]: Could not find the specified arm (serial: PJ000000010301) among the 1 attached devices
[ERROR] [1415117300.684941575]: JacoCommException: Could not find the specified arm (return code: 0)

The serial number is the one that I get on connecting with Jacosoft.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.