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

Support Noetic in Nov #437

Merged
merged 7 commits into from
Nov 12, 2023
Merged
21 changes: 16 additions & 5 deletions .rosinstall.noetic
Original file line number Diff line number Diff line change
Expand Up @@ -6,15 +6,19 @@
uri: https://github.com/jsk-enshu/dynamixel_urdf.git
- git:
local-name: dynamixel_motor
uri: https://github.com/arebgun/dynamixel_motor.git
# uri: https://github.com/arebgun/dynamixel_motor.git
uri: https://github.com/kindsenior/dynamixel_motor.git
version: noetic-support-python3 # need until https://github.com/arebgun/dynamixel_motor/pull/104 wil be merged
- git:
local-name: kobuki
uri: https://github.com/yujinrobot/kobuki.git
version: melodic
- git:
local-name: kobuki_desktop
uri: https://github.com/yujinrobot/kobuki_desktop.git
version: melodic
# uri: https://github.com/yujinrobot/kobuki_desktop.git
# version: melodic
uri: https://github.com/kindsenior/kobuki_desktop.git
version: remove-repeated-tf-publication # need until https://github.com/yujinrobot/kobuki_desktop/pull/69 wil be merged
- git:
local-name: turtlebot
uri: https://github.com/turtlebot/turtlebot.git
Expand All @@ -37,8 +41,10 @@
version: indigo
- git:
local-name: yujin_ocs
uri: https://github.com/yujinrobot/yujin_ocs.git
version: devel # add CATKIN_IGNORE in packages except for cmd_vel_mux, controllers, math_toolkit, velocity_smoother, and virtual_sensor
# uri: https://github.com/yujinrobot/yujin_ocs.git
# version: devel # add CATKIN_IGNORE in packages except for cmd_vel_mux, controllers, math_toolkit, velocity_smoother, and virtual_sensor
uri: https://github.com/kindsenior/yujin_ocs.git
version: noetic-enshu2023 # for ignoring those packages
- git:
local-name: ar_track_alvar_msgs
uri: https://github.com/ros-gbp/ar_track_alvar-release.git
Expand All @@ -63,3 +69,8 @@
# local-name: jsk_pr2eus
# uri: https://github.com/jsk-ros-pkg/jsk_pr2eus.git
# version: master # add CATKIN_IGNORE in packages except for pr2eus
- git:
local-name: jsk_roseus # for disabling warning of tf dupulications
# uri: https://github.com/jsk-ros-pkg/jsk_roseus.git
uri: https://github.com/k-okada/jsk_roseus.git
version: set-log-level-to-error
6 changes: 3 additions & 3 deletions dxl_armed_turtlebot/euslisp/arm-move-sample.l
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@
;;gripper
(send *dxl-armed-turtlebot* :gripper :arm :angle-vector #f(50))
(send *irtviewer* :draw-objects)
(send *ri* :angle-vector (send *dxl-armed-turtlebot* :angle-vector) 1000 :gripper-controller)
(send *ri* :move-gripper (send *dxl-armed-turtlebot* :gripper :arm :joint-angle) :tm 1000 :wait t)
(warn ";;~%")
(warn ";; The gripper was moved. Are real robot and model same? Check it, then press enter~%")
(warn ";;~%")
Expand All @@ -74,12 +74,12 @@
(if (y-or-n-p)
(progn
(send *dxl-armed-turtlebot* :gripper :arm :angle-vector #f(0))
(send *ri* :angle-vector (send *dxl-armed-turtlebot* :angle-vector) 1000 :gripper-controller)
(send *ri* :move-gripper (send *dxl-armed-turtlebot* :gripper :arm :joint-angle) :tm 1000 :wait t)
(send *irtviewer* :draw-objects))
(progn
(warn ";; fix gripper direction!!!~%")
(send *dxl-armed-turtlebot* :gripper :arm :angle-vector #f(0))
(send *ri* :angle-vector (send *dxl-armed-turtlebot* :angle-vector) 1000 :gripper-controller)
(send *ri* :move-gripper (send *dxl-armed-turtlebot* :gripper :arm :joint-angle) :tm 1000 :wait t)
(send *irtviewer* :draw-objects)
(return-from dxl-arm-check)))
;;
Expand Down
18 changes: 9 additions & 9 deletions dynamixel_7dof_arm/scripts/reset_torque.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,10 @@

try:
dxl_io = dynamixel_io.DynamixelIO(port, baudrate)
except dynamixel_io.SerialOpenError, soe:
print 'ERROR:', soe
except dynamixel_io.SerialOpenError as soe:
print('ERROR:', soe)
else:
print 'Turning torque %s for motor %d' % (torque_on, motor_id)
print('Turning torque %s for motor %d' % (torque_on, motor_id))
ret = dxl_io.ping(motor_id)
if ret:
from dynamixel_driver import dynamixel_const
Expand All @@ -44,23 +44,23 @@
elif torque_on.lower() == 'on':
if not ret[4] & dynamixel_const.DXL_OVERHEATING_ERROR == 0:
dxl_io.set_torque_limit(motor_id, 1023)
print "OVERHEATING -> Reset Torque"
print("OVERHEATING -> Reset Torque")
if not ret[4] & dynamixel_const.DXL_OVERLOAD_ERROR == 0:
dxl_io.set_torque_limit(motor_id, 1023)
print "OVERLOAD -> Reset Torque"
print("OVERLOAD -> Reset Torque")
torque_on = True
else:
parser.print_help()
exit(1)
ret = dxl_io.set_torque_enabled(motor_id, torque_on)
if not ret[4] & dynamixel_const.DXL_OVERHEATING_ERROR == 0:
print "OVERHEATING"
print("OVERHEATING")
exit (1)
if not ret[4] & dynamixel_const.DXL_OVERLOAD_ERROR == 0:
print "OVERLOAD"
print("OVERLOAD")
exit (1)
print "done."
print("done.")
else:
print 'ERROR: motor %d did not respond. Make sure to specify the correct baudrate.' % motor_id
print('ERROR: motor %d did not respond. Make sure to specify the correct baudrate.' % motor_id)
exit (1)

12 changes: 6 additions & 6 deletions dynamixel_7dof_arm/scripts/scan_ids.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,12 @@

try:
dxl_io = dynamixel_io.DynamixelIO(port, baudrate)
except dynamixel_io.SerialOpenError, soe:
print 'ERROR:', soe
except dynamixel_io.SerialOpenError as soe:
print('ERROR:', soe)
else:
for idx in map(lambda x : x + options.from_id , range(options.to_id - options.from_id + 1)):
print 'Scanning %d...' %(idx),
for idx in [x + options.from_id for x in range(options.to_id - options.from_id + 1)]:
print('Scanning %d...' %(idx), end=' ')
if dxl_io.ping(idx):
print 'The motor %d respond to a ping' %(idx)
print('The motor %d respond to a ping' %(idx))
else:
print 'ERROR: The specified motor did not respond to id %d.' % idx
print('ERROR: The specified motor did not respond to id %d.' % idx)