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

do not check position/limit error when lower limit and upper limit is same #726

Merged
merged 1 commit into from
Jul 20, 2015
Merged

Conversation

k-okada
Copy link
Contributor

@k-okada k-okada commented Jul 20, 2015

some robot has joint which upper limit and lower limit has same value, for example
https://raw.githubusercontent.com/start-jsk/rtmros_hironx/hydro-devel/hironx_ros_bridge/models/kawada-hironx.dae

                <joint name="WAIST_JOINT" sid="jointsid0">
                    <revolute sid="axis0">
                        <axis>0 0 1</axis>
                        <limits>
                            <min>0</min>
                            <max>0</max>
                        </limits>
                    </revolute>
                </joint>

and this outputs

position limit over (0), qRef=-8.75e-07, llimit =0, ulimit =0, servo_state = ON, prev_angle = 0
velocity limit over (0), qvel=0, lvlimit =0.000175, uvlimit =-0.000175, servo_state = ON
position limit over (0), qRef=-8.75e-07, llimit =0, ulimit =0, servo_state = ON, prev_angle = 0
velocity limit over (0), qvel=0, lvlimit =0.000175, uvlimit =-0.000175, servo_state = ON
position limit over (0), qRef=-8.75e-07, llimit =0, ulimit =0, servo_state = ON, prev_angle = 0
velocity limit over (0), qvel=0, lvlimit =0.000175, uvlimit =-0.000175, servo_state = ON
position limit over (0), qRef=-8.75e-07, llimit =0, ulimit =0, servo_state = ON, prev_angle = 0
velocity limit over (0), qvel=0, lvlimit =0.000175, uvlimit =-0.000175, servo_state = ON
position limit over (0), qRef=-8.75e-07, llimit =0, ulimit =0, servo_state = ON, prev_angle = 0
[ INFO] [1437357214.104381921, 31.414999999]: [HrpsysSeqStateROSBridge0] @onExecutece 0 is working at 202[Hz] (exec 1776 Hz, dropped 202)
velocity limit over (0), qvel=0, lvlimit =0.000175, uvlimit =-0.000175, servo_state = ON
position limit over (0), qRef=-8.75e-07, llimit =0, ulimit =0, servo_state = ON, prev_angle = 0
velocity limit over (0), qvel=0, lvlimit =0.000175, uvlimit =-0.000175, servo_state = ON

https://travis-ci.org/start-jsk/rtmros_common/jobs/71699630

This PR skips limit check if ulimit and ulimit are same (actually if ulimit < llimit)

@k-okada
Copy link
Contributor Author

k-okada commented Jul 20, 2015

Refer to this link for build results (access rights to CI server needed):
http:https://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/hrpsys-qnx/2186/
Test PASSed.

@snozawa
Copy link
Contributor

snozawa commented Jul 20, 2015

Is this dummy joint?

@k-okada
Copy link
Contributor Author

k-okada commented Jul 20, 2015

I think this is originally base 6dof of wrl file and wrongly interpreted by
an old converter

2015年7月20日月曜日、Shunichi [email protected]さんは書きました:

Is this dummy joint?


Reply to this email directly or view it on GitHub
#726 (comment)
.

◉ Kei Okada

@snozawa
Copy link
Contributor

snozawa commented Jul 20, 2015

I see, thanks.

fkanehiro added a commit that referenced this pull request Jul 20, 2015
do not check position/limit error when lower limit and upper limit is same
@fkanehiro fkanehiro merged commit c529373 into fkanehiro:master Jul 20, 2015
@@ -230,7 +230,8 @@ RTC::ReturnCode_t SoftErrorLimiter::onExecute(RTC::UniqueId ec_id)
double qvel = (m_qRef.data[i] - prev_angle[i]) / dt;
double lvlimit = m_robot->joint(i)->lvlimit + 0.000175; // 0.01 deg / sec
double uvlimit = m_robot->joint(i)->uvlimit - 0.000175;
if ( servo_state[i] == 1 && ((lvlimit > qvel) || (uvlimit < qvel)) ) {
// fixed joint has ulimit = vlimit
if ( servo_state[i] == 1 && (uvlimit < uvlimit) && ((lvlimit > qvel) || (uvlimit < qvel)) ) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

こちらですが、
uvlimit < uvlimit
でなくて
lvlimit < uvlimit
ですね。
現状のものだとリミットがかかってない状態になりました。

snozawa added a commit to snozawa/hrpsys-base that referenced this pull request Jul 24, 2015
fkanehiro added a commit that referenced this pull request Jul 24, 2015
Fix bug of Velocity limitation in #726
@k-okada k-okada deleted the fixed_joint branch July 27, 2015 12:54
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

Successfully merging this pull request may close these issues.

None yet

3 participants