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

j2n6s300.xacro and spec sheet does not match the real robot specs #444

Open
yuzhongchun17 opened this issue Aug 12, 2024 · 0 comments
Open

Comments

@yuzhongchun17
Copy link

Description

The spec sheet and the j2n6s300.xacro for the Jaco Gen2 6DoF (non-spherical) specify that joint 5 is a continuous joint with a joint limit ranging from -2π to 2π. However, when testing with the real robot, joint 5 is actually a revolute joint with a limit from 65 to 295 degree, which is the same as the 6DoF spherical version. spec sheet

I also created a fix for this issue #443.

    <xacro:property name="joint_5" value="joint_5" />
    <xacro:property name="joint_5_type" value="continuous" />
    <xacro:property name="joint_5_axis_xyz" value="0 0 1" />
    <xacro:property name="joint_5_origin_xyz" value="0 -0.03703 -0.06414" />
    <xacro:property name="joint_5_origin_rpy" value="${J_PI/3} 0 ${J_PI}" />
    <xacro:property name="joint_5_lower_limit" value="${-2*J_PI}" />
    <xacro:property name="joint_5_upper_limit" value="${2*J_PI}" />
    <xacro:property name="joint_5_velocity_limit" value="${48*J_PI/180}" />
    <xacro:property name="joint_5_torque_limit" value="20" />
    <xacro:property name="joint_5" value="joint_5" />
    <xacro:property name="joint_5_type" value="revolute" />
    <xacro:property name="joint_5_axis_xyz" value="0 0 1" />
    <xacro:property name="joint_5_origin_xyz" value="0 -0.03703 -0.06414" />
    <xacro:property name="joint_5_origin_rpy" value="${J_PI/3} 0 ${J_PI}" />
    <xacro:property name="joint_5_lower_limit" value="${65/180*J_PI}" />
    <xacro:property name="joint_5_upper_limit" value="${295/180*J_PI}" />
    <xacro:property name="joint_5_velocity_limit" value="${48*J_PI/180}" />
    <xacro:property name="joint_5_torque_limit" value="20" />

Version

ROS distribution : Noetic

Branch and commit you are using : noetic-devel

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

1 participant