Kinovarobotics / kinova-ros

ROS packages for Jaco2 and Mico robotic arms
BSD 3-Clause "New" or "Revised" License
378 stars 319 forks source link

Is there a way to monitor the joystick commands or use it to publish ros topics? #396

Closed ericdusel77 closed 2 years ago

ericdusel77 commented 2 years ago

Summary

I would like to be able to monitor the user as they attempt to complete tasks with the joystick for a study I am doing. I was hoping to subscribe to the topics and record a rosbag for later analysis.

Use case

It would be good for data collection and also if I was hoping to control a larger robotic system (wheelchair navigation for example) using the joystick by publishing relevant messages.

Additional context

I would like to do a study on how much user input is required to complete certain tasks.

felixmaisonneuve commented 2 years ago

Hi @ericdusel77,

Looking at the API, there is a GetJoystickValue call that seems to give the joystick values. I haven't tried it, but you could create a ROS topic in the driver that publishes the values of that API call and monitor this topic with rosbag.

If it doesn't work, you could create your own topic based on the SendJoystickCommand API call and monitor this. You would have to simulate actual joystick commands in your code, but it might be just enough for you to get the data you want.

Best, Felix

ericdusel77 commented 2 years ago

Hello Felix. Thank you for the quick response! I have been trying to work through this with the api command. It looks like there is something called "ButtonValue" in the JoystickCommand structure. The length of the array is 32, is there a way to know what the 32 buttons correspond to?

Thank you, -end

ericdusel77 commented 2 years ago

As a follow up to my previous message, I have written a node that attempts to publish all (32) of the joystick commands in a string form (cuz that was the simplest way I could think to do it).

Anywho, it seems to print 0 for all of the button values. I have pasted the code below:

#include "kinova_driver/kinova_api.h"
#include <ros/ros.h>
#include "std_msgs/String.h"
#include <string>

int main(int argc, char **argv)
{
    ros::init(argc, argv, "joystick_pub");
    ros::NodeHandle nh;

    ros::Publisher joy_pub = nh.advertise<std_msgs::String>("joystick_command", 10);

    kinova::KinovaAPI kinova_api_;
    kinova_api_.initializeKinovaAPIFunctions(kinova::USB);

    while (ros::ok())
    {

        JoystickCommand j;
        j.InitStruct();

        int result = kinova_api_.getJoystickValue(j);
        std_msgs::String b_val;
        int idx;
        std::string joystick = "";
        // CANNOT LOOP FROM 0-32 FOR SOME REASON, SO THIS DOUBLE LOOP AVOIDS THE SEGFAULT AND CATCHES ALL 32 BUTTONVALUES
        for (int v = 0; v < 2; v++)
        {    
            for (int i = 0; i < 16; i++){
                if (v){idx=i+16;}
                else{idx=i;}
                joystick = joystick+std::to_string(j.ButtonValue[idx]);
            }
        }

        b_val.data = joystick;
        joy_pub.publish(b_val);

    }

    return 0;
}

According to the API, it should be switching from 0 to 1 when the button is PRESSED (see KinovaTypes.h).

Any idea why this does not work? I notice that when similar functions are used inside of kinovacomm, there is some mutex consideration, but to be honest this is beyond my understanding so I was hoping it wasn't necessary for simply tracking the ButtonValues.

Thank you, -end

felixmaisonneuve commented 2 years ago

Looking at KinovaTypes.h, the length of ButtonValue seems to be only 16, but I am sure I have seen 32 somewhere (in the doc maybe?). In any case, you are probably more interested in the joystick movements (InclineLeftRight, InclineForwardBackward, Rotate, ...), no?

https://github.com/Kinovarobotics/kinova-ros/blob/93f66822ec073827eac5de59ebc2a3c5f06bf17f/kinova_driver/include/kinova/KinovaTypes.h#L884-L944

I assume ButtonValue corresponds to the actual buttons on the joystick, and I suppose we only use a small portion of them based on the controller used.

ericdusel77 commented 2 years ago

Yes! I definitely would prefer those values. However, I am still having trouble getting anything except 0.0. Thoughts?

#include "kinova_driver/kinova_api.h"
#include <ros/ros.h>
#include "std_msgs/Float64.h"

int main(int argc, char **argv)
{
    ros::init(argc, argv, "joystick_pub");
    ros::NodeHandle nh;

    ros::Publisher joy_pub = nh.advertise<std_msgs::Float64>("joystick_command", 10);

    kinova::KinovaAPI kinova_api_;
    kinova_api_.initializeKinovaAPIFunctions(kinova::KinovaAPIType::USB);
    int result;

    result = kinova_api_.startControlAPI();

    while (ros::ok())
    {

        JoystickCommand j;
        j.InitStruct();

        result = kinova_api_.getJoystickValue(j);

        std_msgs::Float64 b_val;

        b_val.data = j.Rotate;
        joy_pub.publish(b_val);

    }

    return 0;
}
felixmaisonneuve commented 2 years ago

I tested it. I created a topic for the joystick value using the GetJoystickValue call. When using the joystick I see the values being updated. It works very well for up/down, left/right and rotate commands (the default kinova joystick does not allow other movement types) image

I added a new function in void getJoystickValue(JoystickCommand &command); in kinova_comm.h and this is the function in kinova_comm.cpp :

/**
 * @brief This function is for testing purposes.
 */
void KinovaComm::getJoystickValue(JoystickCommand &command)
{
    boost::recursive_mutex::scoped_lock lock(api_mutex_);
    memset(&command, 0, sizeof(command));  // zero structure

    int result = kinova_api_.getJoystickValue(command);
    if (result != NO_ERROR_KINOVA)
    {
        throw KinovaCommException("Could not get Joystick Values", result);
    }
}

then I added a ros::Publisher joystick_values_publisher_; in kinova_arm.h, initialized it in KinovaArm(...). (I used kinova_msgs::JointAngles because it already exists and I am lazy, but you could create your own message with what you need)

    joystick_values_publisher_ = node_handle_.advertise<kinova_msgs::JointAngles>
            ("out/joystick_values", 2);

then I published the values in publishFingerPosition(void) in Kinova_arm.cpp (again, you could create your own function for joystick commands)

    JoystickCommand command;
    kinova_comm_.getJoystickValue(command);
    kinova_msgs::JointAngles joystick;
    joystick.joint1       = command.InclineLeftRight;
    joystick.joint2 = command.InclineForwardBackward;
    joystick.joint3                 = command.Rotate;
    joystick.joint4          = command.MoveLeftRight;
    joystick.joint5    = command.MoveForwardBackward;
    joystick.joint6               = command.PushPull;

    joystick_values_publisher_.publish(joystick);

You then have to compile with catkin_make and you should be good to go.

I am not sure why it does not work in your case. My guess is startControlAPI is not working probably because you have another node running and you cannot connect 2 times at the same time (e.g. 2 ros nodes or the ros driver and Development Center) You could probably print the value of result and check if you are curious

Regards, Felix

ericdusel77 commented 2 years ago

Unfortunately, it does not appear to work on my end, after copying your steps.

I think this is because I am on a Jaco gen 1, with a firmware that may not be compatible with this feature? (v 5.1.0)

felixmaisonneuve commented 2 years ago

Ok, yes, this is it. These function calls are not implemented in the base firmware v5.1.0

In that case, I think it is not possible for you to monitor joystick commands. I do not know what the API looks like what function is/is not available. You could maybe try to monitor the cartesian velocities of the arm and deduce the joystick command?

felixmaisonneuve commented 2 years ago

Hi @ericdusel77,

Have you tried monitoring cartesian velocities instead?

Can we close this issue?

Regards, Felix