diff --git a/.rosinstall.noetic b/.rosinstall.noetic index d58e37b2..c51cd454 100644 --- a/.rosinstall.noetic +++ b/.rosinstall.noetic @@ -74,3 +74,7 @@ # 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 +- git: + local-name: ros_controllers + uri: https://github.com/ros-controls/ros_controllers.git + version: 0.20.0 # after this version, ros_control does not publish /motor1/position based on /position_trajectory_controller/command from /rqt_joint_trajectory_controller because of the same warning https://github.com/ros-controls/ros_controllers/issues/291 \ No newline at end of file diff --git a/mechatrobot/launch/sample_face_detect.launch b/mechatrobot/launch/sample_face_detect.launch index 26f88890..98f8fee0 100644 --- a/mechatrobot/launch/sample_face_detect.launch +++ b/mechatrobot/launch/sample_face_detect.launch @@ -10,6 +10,9 @@ + + + diff --git a/mechatrobot/scripts/motor-command-by-face.py b/mechatrobot/scripts/motor-command-by-face.py index 5421c442..f5c3f907 100755 --- a/mechatrobot/scripts/motor-command-by-face.py +++ b/mechatrobot/scripts/motor-command-by-face.py @@ -5,7 +5,7 @@ from std_msgs.msg import Int64 image_size = [640, 480] # pixel -image_center = list(map(lambda x: x/2, image_size)) +image_center = list([x/2 for x in image_size]) motor_angle = 0 # [deg] def face_detection_cb(msg): @@ -29,13 +29,13 @@ def face_detection_cb(msg): motor_command_msg.data = motor_angle # print - print "face_pos(x, y): ({} {})".format(face_pos[0], face_pos[1]) - print "/motor1/command: {}\n".format(motor_command_msg.data) + print("face_pos(x, y): ({} {})".format(face_pos[0], face_pos[1])) + print("/motor1/command: {}\n".format(motor_command_msg.data)) # publish pub.publish(motor_command_msg) else: - print "no faces" + print("no faces") def main():