diff --git a/rcb4/rcb4interface.py b/rcb4/rcb4interface.py
index 21cd7e0b..3bbe6793 100644
--- a/rcb4/rcb4interface.py
+++ b/rcb4/rcb4interface.py
@@ -102,7 +102,6 @@ class RCB4Interface(object):
# The maximum total byte count of motion data
MotionDataCount = 2048 * 120
-
def __init__(self):
self.lock = Lock()
self.serial = None
@@ -283,7 +282,7 @@ def move_com_to_ram_command(dest_addr, dest_data):
txbuf.append(CommandTypes.Move.value)
txbuf.append(SubMoveCmd.ComToRam.value)
txbuf.append(dest_addr & 0xff)
- txbuf.append((dest_addr >> 8 ) & 0xff)
+ txbuf.append((dest_addr >> 8) & 0xff)
txbuf.append(0x00)
if len(dest_data) == 1:
txbuf.append(dest_data[0])
@@ -630,9 +629,10 @@ def get_config(self):
def call_command(self, rom_addr):
"""Creates a command to call a specified ROM address.
- This method generates a command array to be sent to a device, instructing it
- to perform a jump to the specified ROM address. This function is static and
- can be accessed externally without an instance of the class.
+ This method generates a command array to be sent to a device,
+ instructing it to perform a jump to the specified ROM address.
+ This function is static and can be accessed externally without
+ an instance of the class.
Parameters
----------
@@ -645,13 +645,14 @@ def call_command(self, rom_addr):
return_data_size : int
The size of the data expected to be returned by the command.
txbuf : list of int
- The list representing the entire command to be sent, including the
- command to call the ROM address, the address itself, and the checksum.
+ The list representing the entire command to be sent,
+ including the command to call the ROM address, the address
+ itself, and the checksum.
Notes
-----
- The command created by this function does not check conditions before calling
- the specified address.
+ The command created by this function does not check conditions before
+ calling the specified address.
Warnings
--------
@@ -796,14 +797,16 @@ def resume_motion(self):
Notes
-----
Modifies the config data to resume the motion.
- Direct manipulation of internal config data (`self._config_data`) is involved.
+ Direct manipulation of internal config data
+ (`self._config_data`) is involved.
"""
self._config_data |= ConfigData.EnableRunEeprom.value
self._config_data &= ~ConfigData.EnableServoResponse.value
self._config_data |= ConfigData.EnableReferenceTable.value
self._config_data |= ConfigData.EnableSio.value
buf = [self._config_data & 0xff, (self._config_data >> 8) & 0xff]
- return self.write_move_com_to_ram_command(RamAddr.ConfigRamAddress.value, buf)
+ return self.write_move_com_to_ram_command(
+ RamAddr.ConfigRamAddress.value, buf)
def play_motion(self, motion_num):
"""Plays the specified motion.
diff --git a/ros/kxr_controller/CMakeLists.txt b/ros/kxr_controller/CMakeLists.txt
index 778f6ef6..eb981805 100644
--- a/ros/kxr_controller/CMakeLists.txt
+++ b/ros/kxr_controller/CMakeLists.txt
@@ -114,4 +114,6 @@ if(CATKIN_ENABLE_TESTING)
endif()
add_rostest(test/kxr_controller.test ARGS namespace:="")
add_rostest(test/kxr_controller.test ARGS namespace:="robot_a")
+ add_rostest(test/kxr_controller.test ARGS namespace:="" use_rcb4:=true)
+ add_rostest(test/kxr_controller.test ARGS namespace:="robot_a" use_rcb4:=true)
endif()
diff --git a/ros/kxr_controller/launch/kxr_controller.launch b/ros/kxr_controller/launch/kxr_controller.launch
index 0aa8d751..4ad02281 100644
--- a/ros/kxr_controller/launch/kxr_controller.launch
+++ b/ros/kxr_controller/launch/kxr_controller.launch
@@ -6,6 +6,7 @@
+
@@ -19,6 +20,7 @@
servo_config_path: $(arg servo_config_path)
publish_imu: $(arg publish_imu)
imu_frame_id: $(arg namespace)/$(arg imu_frame_id)
+ use_rcb4: $(arg use_rcb4)
@@ -36,6 +38,7 @@
servo_config_path: $(arg servo_config_path)
publish_imu: $(arg publish_imu)
imu_frame_id: $(arg imu_frame_id)
+ use_rcb4: $(arg use_rcb4)
diff --git a/ros/kxr_controller/node_scripts/rcb4_ros_bridge.py b/ros/kxr_controller/node_scripts/rcb4_ros_bridge.py
index d831d8f9..08225ba1 100644
--- a/ros/kxr_controller/node_scripts/rcb4_ros_bridge.py
+++ b/ros/kxr_controller/node_scripts/rcb4_ros_bridge.py
@@ -18,6 +18,7 @@
import yaml
from rcb4.armh7interface import ARMH7Interface
+from rcb4.rcb4interface import RCB4Interface
np.set_printoptions(precision=0, suppress=True)
@@ -129,7 +130,11 @@ def __init__(self):
JointState,
queue_size=1)
- self.interface = ARMH7Interface.from_port()
+ if rospy.get_param('~use_rcb4'):
+ self.interface = RCB4Interface()
+ self.interface.auto_open()
+ else:
+ self.interface = ARMH7Interface.from_port()
if self.interface is None:
rospy.logerr('Could not open port!')
sys.exit(1)
@@ -185,6 +190,8 @@ def __init__(self):
clean_namespace)
self.publish_imu = rospy.get_param('~publish_imu', True)
+ if self.interface.__class__.__name__ == 'RCB4Interface':
+ self.publish_imu = False
if self.publish_imu:
self.imu_frame_id = rospy.get_param(
'~imu_frame_id', clean_namespace + '/' + r.root_link.name)
diff --git a/ros/kxr_controller/test/kxr_controller.test b/ros/kxr_controller/test/kxr_controller.test
index 29209365..88971b74 100644
--- a/ros/kxr_controller/test/kxr_controller.test
+++ b/ros/kxr_controller/test/kxr_controller.test
@@ -1,11 +1,13 @@
+
+
@@ -13,23 +15,34 @@
name="test_ros_topics"
pkg="jsk_tools" type="test_topic_published.py"
retry="1" >
-
- topic_0: current_joint_states
- timeout_0: 30
- topic_1: joint_states
- timeout_1: 30
- topic_2: kxr_fullbody_controller/follow_joint_trajectory/status
- timeout_2: 30
- topic_3: kxr_fullbody_controller/servo_on_off_real_interface/status
- timeout_3: 30
- topic_4: kxr_fullbody_controller/servo_on_off/status
- timeout_4: 30
- topic_5: imu
- timeout_5: 30
-
+
+ topic_0: current_joint_states
+ timeout_0: 30
+ topic_1: joint_states
+ timeout_1: 30
+ topic_2: kxr_fullbody_controller/follow_joint_trajectory/status
+ timeout_2: 30
+ topic_3: kxr_fullbody_controller/servo_on_off_real_interface/status
+ timeout_3: 30
+ topic_4: kxr_fullbody_controller/servo_on_off/status
+ timeout_4: 30
+
+
+
+
+
+ topic_0: imu
+ timeout_0: 30
+
+
+
+
+
+
+
+
+ topic_0: imu
+ timeout_0: 30
+
+
+
2.0):
+ raise AssertionError(
+ "Servo angles are beyond the acceptable range.")
+
+ time.sleep(1.0)
+ self.interface.neutral()
+ time.sleep(4.0)
+ self.interface.free()