Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

No data from active joint encoders #3

Closed
kamilcetin opened this issue Jun 5, 2023 · 10 comments
Closed

No data from active joint encoders #3

kamilcetin opened this issue Jun 5, 2023 · 10 comments

Comments

@kamilcetin
Copy link

Hi,

I have 3D Systems' Touch device and run this package and device with ROS noetic on Ubuntu 20.04. I can calibrate and read all encoder data from Touch_Diagnostic. When I do roslaunch geomagic_control geomagic_headless.launch, I have these ros topic list:
rostopic list
/Geomagic/button
/Geomagic/force_feedback
/Geomagic/joint_states
/Geomagic/joy
/Geomagic/pose
/Geomagic/twist
/rosout
/rosout_agg
/tf
/tf_static

When I echo all ros topics, I recognize that there is data coming from buttons and passive wrist joints (from gimbal encoders) but not from active joints such as

when I do rostopic echo /Geomagic/joint_states, only gimbal positions are published:
position: [-0.0, 0.0, 0.0, 2.5234922488504132, -2.9634022653083116, 4.908947141962596]

or when I do rostopic echo /Geomagic/pose, only orientation data are published:
pose:
position:
x: 0.0
y: -110.0
z: -35.0
orientation:
x: -0.405031046104968
y: -0.036064943439096685
z: -0.6450909096350691
w: 0.6469210967625927

Do you know that is there any reason for that?

Thanks,
KC

@adnanmunawar
Copy link
Member

Hi Kamil,

Hmm, that is odd, I haven't see this before. Can you try one thing, close the ros application, (i.e. terminate roslaunch geomagic_control geomagic_headless.launch). Then take the stylus out of the ink-well and after this rerun the roslaunch geomagic_control geomagic_headless.launch command. Is there any change?

@kamilcetin
Copy link
Author

Hi Adnan,

I tried it. But it does not change. I mean that three active encoder joint positions are still 0,0,0 and pose.positions x,y,z are still 0,-110,-35. However, the other gimbal positions and orientation are changing.

It is really strange case.

@adnanmunawar
Copy link
Member

Yeah I haven't seen this one before. I do not have a device with me for a few months to test this out for myself. Looking at the code, the joints are being read here

HDCallbackCode HDCALLBACK device_state_callback(void *pUserData) {
    DeviceState *device_state = static_cast<DeviceState *>(pUserData);
    if (hdCheckCalibration() == HD_CALIBRATION_NEEDS_UPDATE) {
        ROS_DEBUG("Updating calibration...");
        hdUpdateCalibration(calibrationStyle);
    }
    hdBeginFrame(hdGetCurrentDevice());
    //Get angles, set forces
    hdGetDoublev(HD_CURRENT_GIMBAL_ANGLES, device_state->rot);
    hdGetDoublev(HD_CURRENT_POSITION, device_state->position);
    hdGetDoublev(HD_CURRENT_JOINT_ANGLES, device_state->joints);
    hdGetDoublev(HD_CURRENT_TRANSFORM, device_state->transform);

    hduVector3Dd vel_buff(0, 0, 0);
    vel_buff = (device_state->position * 3 - 4 * device_state->pos_hist1
                + device_state->pos_hist2) / 0.002;  //mm/s, 2nd order backward dif
    device_state->velocity = (.2196 * (vel_buff + device_state->inp_vel3)
                              + .6588 * (device_state->inp_vel1 + device_state->inp_vel2)) / 1000.0
            - (-2.7488 * device_state->out_vel1 + 2.5282 * device_state->out_vel2
               - 0.7776 * device_state->out_vel3);  //cutoff freq of 20 Hz
    device_state->pos_hist2 = device_state->pos_hist1;
    device_state->pos_hist1 = device_state->position;
    device_state->inp_vel3  = device_state->inp_vel2;
    device_state->inp_vel2  = device_state->inp_vel1;
    device_state->inp_vel1  = vel_buff;
    device_state->out_vel3  = device_state->out_vel2;
    device_state->out_vel2  = device_state->out_vel1;
    device_state->out_vel1  = device_state->velocity;
    for(int i=0; i<3;i++){
        if (device_state->lock[i]) {
            device_state->force[i] = 0.3 * (device_state->lock_pos[i] - device_state->position[i])
                    - 0.001 * device_state->velocity[i];
        }
    }
    hdSetDoublev(HD_CURRENT_FORCE, device_state->force);

    //Get buttons
    int nButtons = 0;
    hdGetIntegerv(HD_CURRENT_BUTTONS, &nButtons);
    device_state->buttons[0] = (nButtons & HD_DEVICE_BUTTON_1) ? 1 : 0;
    device_state->buttons[1] = (nButtons & HD_DEVICE_BUTTON_2) ? 1 : 0;

    hdEndFrame(hdGetCurrentDevice());

    HDErrorInfo error;
    if (HD_DEVICE_ERROR(error = hdGetError())) {
        hduPrintError(stderr, &error, "Error during main scheduler callback");
        if (hduIsSchedulerError(&error))
            return HD_CALLBACK_DONE;
    }

    float t[7] = { 0., device_state->joints[0], device_state->joints[1],
                   device_state->joints[2] - device_state->joints[1], device_state->rot[0],
                   device_state->rot[1], device_state->rot[2] };
    for (int i = 0; i < 7; i++)
        device_state->thetas[i] = t[i];
    return HD_CALLBACK_CONTINUE;
}

It may be possible that there in an update to the libHD API and we just need to incorporate that.

@RaMathuZen
Copy link

I am using a Geomagic Touch device with an ethernet connection. I did run roslaunch geomagic_control geomagic.launch and I am able to interface it with ROS noetic in Linux Mint 20.3 which is based on Ubuntu Focal 20.04. Also I am able to recieve those data.

@kamilcetin
Copy link
Author

kamilcetin commented Jun 8, 2023

Hi, I have noticed that when I do catkin_make I have no errors but have some warnings;

Scanning dependencies of target device_node
[ 85%] Built target geomagic_control_generate_messages
[ 92%] Building CXX object ros_geomagic/geomagic_control/CMakeFiles/device_node.dir/src/device_node.cpp.o
/home/kamil/catkin_ws/src/ros_geomagic/geomagic_control/src/device_node.cpp:250:64: warning: ‘stdcall’ attribute ignored [-Wattributes]
250 | HDCallbackCode HDCALLBACK device_state_callback(void pUserData) {
| ^
/home/kamil/catkin_ws/src/ros_geomagic/geomagic_control/src/device_node.cpp: In function ‘HDCallbackCode device_state_callback(void
)’:
/home/kamil/catkin_ws/src/ros_geomagic/geomagic_control/src/device_node.cpp:303:63: warning: narrowing conversion of ‘device_state->DeviceState::joints.hduVector3D::operator’ from ‘double’ to ‘float’ [-Wnarrowing]
303 | device_state->rot[1], device_state->rot[2] };
| ^
/home/kamil/catkin_ws/src/ros_geomagic/geomagic_control/src/device_node.cpp:303:63: warning: narrowing conversion of ‘device_state->DeviceState::joints.hduVector3D::operator’ from ‘double’ to ‘float’ [-Wnarrowing]
/home/kamil/catkin_ws/src/ros_geomagic/geomagic_control/src/device_node.cpp:302:44: warning: narrowing conversion of ‘(device_state->DeviceState::joints.hduVector3D::operator - device_state->DeviceState::joints.hduVector3D::operator)’ from ‘double’ to ‘float’ [-Wnarrowing]
302 | device_state->joints[2] - device_state->joints[1], device_state->rot[0],
/home/kamil/catkin_ws/src/ros_geomagic/geomagic_control/src/device_node.cpp:303:63: warning: narrowing conversion of ‘device_state->DeviceState::rot.hduVector3D::operator’ from ‘double’ to ‘float’ [-Wnarrowing]
303 | device_state->rot[1], device_state->rot[2] };
| ^
/home/kamil/catkin_ws/src/ros_geomagic/geomagic_control/src/device_node.cpp:303:63: warning: narrowing conversion of ‘device_state->DeviceState::rot.hduVector3D::operator’ from ‘double’ to ‘float’ [-Wnarrowing]
/home/kamil/catkin_ws/src/ros_geomagic/geomagic_control/src/device_node.cpp:303:63: warning: narrowing conversion of ‘device_state->DeviceState::rot.hduVector3D::operator’ from ‘double’ to ‘float’ [-Wnarrowing]
[100%] Linking CXX executable /home/kamil/catkin_ws/devel/lib/geomagic_control/device_node
/usr/bin/ld: warning: libncurses.so.5, needed by /usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/libHD.so, may conflict with libncurses.so.6
[100%] Built target device_node

When I checked my Ubuntu folders, I have both libncurses.so.5 and libncurses.so.6:
/usr/lib/x86_64-linux-gnu/libncurses.so.5
/usr/lib/x86_64-linux-gnu/libncurses.so.5.9
/usr/lib/x86_64-linux-gnu/libncurses.so.6
/usr/lib/x86_64-linux-gnu/libncurses.so.6.2

Do you think that the problem is related with incorporation between the code and libHD.so or confliction between libncurses.so.5 and libncurses.so.6 ?

@adnanmunawar
Copy link
Member

I don't think that libncurses would cause this runtime issue. Can you try modifying these two lines as below and recompiling and retrying.

Screenshot from 2023-06-08 09-44-07

@kamilcetin
Copy link
Author

It does not change for publishg sensor data.

But, when I do catkin_make, now there is no warnings about double / floating. However, there is still warning for conflict on libncurses:

Scanning dependencies of target device_node
[ 85%] Built target geomagic_control_generate_messages
[ 92%] Building CXX object ros_geomagic/geomagic_control/CMakeFiles/device_node.dir/src/device_node.cpp.o
/home/kamil/catkin_ws/src/ros_geomagic/geomagic_control/src/device_node.cpp:250:64: warning: ‘stdcall’ attribute ignored [-Wattributes]
250 | HDCallbackCode HDCALLBACK device_state_callback(void *pUserData) {
| ^
[100%] Linking CXX executable /home/kamil/catkin_ws/devel/lib/geomagic_control/device_node
/usr/bin/ld: warning: libncurses.so.5, needed by /usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/libHD.so, may conflict with libncurses.so.6
[100%] Built target device_node

@kamilcetin
Copy link
Author

SOLVED :)

In case you have some troubles and your first 3 values are 0, you probably don't have English set as main language. Thats a problem coming from Open Haptics. Simply add this to your ~/.bashrc

export LC_ALL=en_US.UTF-8

This is already written in Readme.md files. But I solved the issue changing all language settings as en_US.UTF-8 on my ubuntu.

@Bala1411
Copy link

I am using a Geomagic Touch device with an ethernet connection. I did run roslaunch geomagic_control geomagic.launch and I am able to interface it with ROS noetic in Linux Mint 20.3 which is based on Ubuntu Focal 20.04. Also I am able to recieve those data.

@RaMathuZen
I am trying to control my robot with Geo magic touch device with Ubuntu Focal 20.04. Can you please tell me the procedure and ros packages you used to get the output? It will be very useful for me.

@RaMathuZen
Copy link

I am using a Geomagic Touch device with an ethernet connection. I did run roslaunch geomagic_control geomagic.launch and I am able to interface it with ROS noetic in Linux Mint 20.3 which is based on Ubuntu Focal 20.04. Also I am able to recieve those data.

@RaMathuZen I am trying to control my robot with Geo magic touch device with Ubuntu Focal 20.04. Can you please tell me the procedure and ros packages you used to get the output? It will be very useful for me.

Yeah I can . Ping me through mail, my mail ID is in my GitHub profile.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants