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

Publish gyro info #14

Merged
merged 2 commits into from
Jan 12, 2024
Merged

Publish gyro info #14

merged 2 commits into from
Jan 12, 2024

Conversation

708yamaguchi
Copy link
Collaborator

Publish gyro info as well as accelerometer info.

$ rostopic echo /imu

Before

header: 
  seq: 72
  stamp: 
    secs: 1704953902
    nsecs: 635263919
  frame_id: "/bodyset94472077639384"
orientation: 
  x: 0.989590585231781
  y: 0.13808977603912354
  z: 0.020743228495121002
  w: 0.03468123450875282
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity: 
  x: 0.0
  y: 0.0
  z: 0.0
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration: 
  x: 0.0
  y: 0.0
  z: 0.0
linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

After

header:                   
  seq: 1080                                                          
  stamp:         
    secs: 1704977204    
    nsecs: 487167119     
  frame_id: "/bodyset94472077639384"
orientation:                                                              
  x: 0.13125546276569366
  y: 0.9903165698051453
  z: 0.04510028660297394
  w: -0.0015717060305178165
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]        
angular_velocity:
  x: 0.33313000202178955      
  y: -0.6373499631881714
  z: -0.36155006289482117
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration:
  x: 0.0
  y: 0.0
  z: 0.0
linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

@708yamaguchi
Copy link
Collaborator Author

My test code

#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Imu


def callback(msg):
    x_impact = msg.angular_velocity.x ** 2
    y_impact = msg.angular_velocity.y ** 2
    z_impact = msg.angular_velocity.z ** 2
            
    if x_impact > 500:
        rospy.loginfo("Detect touch, x axis. {}".format(x_impact))
    if y_impact > 500:
        rospy.loginfo("Detect touch, y axis. {}".format(y_impact))
    if z_impact > 500:
        rospy.loginfo("Detect touch, z axis. {}".format(z_impact))

def listener():
    rospy.init_node('listener', anonymous=True)
    rospy.Subscriber("imu", Imu, callback, queue_size=10)
    rospy.spin()

if __name__ == '__main__':
    listener()

@iory iory force-pushed the publish-gyro-info branch 2 times, most recently from f9cf2d7 to 94a27e2 Compare January 12, 2024 03:58
@iory iory force-pushed the publish-gyro-info branch from 94a27e2 to f201e04 Compare January 12, 2024 04:15
@iory
Copy link
Owner

iory commented Jan 12, 2024

LGTM!

@iory iory merged commit 0677d9e into iory:master Jan 12, 2024
3 checks passed
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.

2 participants