Skip to content

Commit

Permalink
Enable publishing imu (#12)
Browse files Browse the repository at this point in the history
  • Loading branch information
iory authored Jan 10, 2024
1 parent d1450a0 commit 593603a
Show file tree
Hide file tree
Showing 3 changed files with 33 additions and 0 deletions.
6 changes: 6 additions & 0 deletions ros/kxr_controller/launch/kxr_controller.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
<arg name="urdf_path" default="$(find kxr_models)/urdf/kxrl2l2a6h2m.urdf" />
<arg name="servo_config_path" default="$(find kxr_models)/config/kxrl2l2a6h2m_servo_config.yaml" />
<arg name="namespace" default="" />
<arg name="publish_imu" default="true" />
<arg name="imu_frame_id" default="/bodyset94472077639384" />

<group if="$(eval len(arg('namespace')) > 0)" ns="$(arg namespace)" >
<node name="rcb4_ros_bridge"
Expand All @@ -13,6 +15,8 @@
<rosparam subst_value="true" >
urdf_path: $(arg urdf_path)
servo_config_path: $(arg servo_config_path)
publish_imu: $(arg publish_imu)
imu_frame_id: $(arg namespace)/$(arg imu_frame_id)
</rosparam>
</node>

Expand All @@ -36,6 +40,8 @@
<rosparam subst_value="true" >
urdf_path: $(arg urdf_path)
servo_config_path: $(arg servo_config_path)
publish_imu: $(arg publish_imu)
imu_frame_id: $(arg imu_frame_id)
</rosparam>
</node>

Expand Down
23 changes: 23 additions & 0 deletions ros/kxr_controller/node_scripts/rcb4_ros_bridge.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
from kxr_controller.msg import ServoOnOffResult
import numpy as np
import rospy
import sensor_msgs.msg
from sensor_msgs.msg import JointState
from skrobot.model import RobotModel
from skrobot.utils.urdf import no_mesh_load_mode
Expand Down Expand Up @@ -194,6 +195,15 @@ def __init__(self):
self.proc_robot_state_publisher = run_robot_state_publisher(
clean_namespace)

self.publish_imu = rospy.get_param('~publish_imu', True)
if self.publish_imu:
self.imu_frame_id = rospy.get_param(
'~imu_frame_id', clean_namespace + '/' + r.root_link.name)
self.imu_publisher = rospy.Publisher(
clean_namespace + '/imu',
sensor_msgs.msg.Imu,
queue_size=1)

def velocity_command_joint_state_callback(self, msg):
servo_ids = []
av_length = len(self.arm.servo_sorted_ids)
Expand Down Expand Up @@ -315,6 +325,15 @@ def servo_on_off_callback(self, goal):
self.arm.servo_angle_vector(servo_ids, servo_vector, velocity=10)
return self.servo_on_off_server.set_succeeded(ServoOnOffResult())

def create_imu_message(self):
msg = sensor_msgs.msg.Imu()
msg.header.frame_id = self.imu_frame_id
msg.header.stamp = rospy.Time.now()
q_wxyz = self.arm.read_quaternion()
(msg.orientation.w, msg.orientation.x,
msg.orientation.y, msg.orientation.z) = q_wxyz
return msg

def run(self):
rate = rospy.Rate(100)

Expand All @@ -335,6 +354,10 @@ def run(self):
av[self.id_to_index[servo_id]]))
msg.name.append(name)
self.current_joint_states_pub.publish(msg)

if self.publish_imu:
imu_msg = self.create_imu_message()
self.imu_publisher.publish(imu_msg)
rate.sleep()


Expand Down
4 changes: 4 additions & 0 deletions ros/kxr_controller/test/kxr_controller.test
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@
timeout_3: 30
topic_4: kxr_fullbody_controller/servo_on_off/status
timeout_4: 30
topic_5: imu
timeout_5: 30
</rosparam>
</test>
</group>
Expand All @@ -44,6 +46,8 @@
timeout_3: 30
topic_4: kxr_fullbody_controller/servo_on_off/status
timeout_4: 30
topic_5: imu
timeout_5: 30
</rosparam>
</test>
</group>
Expand Down

1 comment on commit 593603a

@github-actions
Copy link

Choose a reason for hiding this comment

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

Please sign in to comment.