|
float | imu_node.accel_factor = 9.806 |
|
| imu_node.accel_x_max = rospy.get_param('~accel_x_max', 250.0) |
|
| imu_node.accel_x_min = rospy.get_param('~accel_x_min', -250.0) |
|
| imu_node.accel_y_max = rospy.get_param('~accel_y_max', 250.0) |
|
| imu_node.accel_y_min = rospy.get_param('~accel_y_min', -250.0) |
|
| imu_node.accel_z_max = rospy.get_param('~accel_z_max', 250.0) |
|
| imu_node.accel_z_min = rospy.get_param('~accel_z_min', -250.0) |
|
| imu_node.angular_velocity_covariance |
|
| imu_node.calib_data = ser.readlines() |
|
string | imu_node.calib_data_print = "Printing set calibration values:\r\n" |
|
| imu_node.calibration_magn_use_extended = rospy.get_param('~calibration_magn_use_extended', False) |
|
float | imu_node.degrees2rad = math.pi/180.0 |
|
| imu_node.diag_arr = DiagnosticArray() |
|
| imu_node.diag_msg = DiagnosticStatus() |
|
| imu_node.diag_pub = rospy.Publisher('diagnostics', DiagnosticArray, queue_size=1) |
|
| imu_node.diag_pub_time = rospy.get_time(); |
|
| imu_node.discard = ser.readlines() |
| configure board ### stop datastream More...
|
|
int | imu_node.errcount = 0 |
|
| imu_node.frame_id = rospy.get_param('~frame_id', 'base_imu_link') |
|
| imu_node.gyro_average_offset_x = rospy.get_param('~gyro_average_offset_x', 0.0) |
|
| imu_node.gyro_average_offset_y = rospy.get_param('~gyro_average_offset_y', 0.0) |
|
| imu_node.gyro_average_offset_z = rospy.get_param('~gyro_average_offset_z', 0.0) |
|
float | imu_node.imu_yaw_calibration = 0.0 |
|
| imu_node.imuMsg = Imu() |
|
| imu_node.level |
|
| imu_node.line = bytearray(row).decode("utf-8") |
|
| imu_node.linear_acceleration_covariance |
|
| imu_node.magn_ellipsoid_center = rospy.get_param('~magn_ellipsoid_center', [0, 0, 0]) |
|
| imu_node.magn_ellipsoid_transform = rospy.get_param('~magn_ellipsoid_transform', [[0, 0, 0], [0, 0, 0], [0, 0, 0]]) |
|
| imu_node.magn_x_max = rospy.get_param('~magn_x_max', 600.0) |
|
| imu_node.magn_x_min = rospy.get_param('~magn_x_min', -600.0) |
|
| imu_node.magn_y_max = rospy.get_param('~magn_y_max', 600.0) |
|
| imu_node.magn_y_min = rospy.get_param('~magn_y_min', -600.0) |
|
| imu_node.magn_z_max = rospy.get_param('~magn_z_max', 600.0) |
|
| imu_node.magn_z_min = rospy.get_param('~magn_z_min', -600.0) |
|
| imu_node.message |
|
| imu_node.name |
|
| imu_node.orientation_covariance |
|
int | imu_node.pitch = 0 |
|
| imu_node.port = rospy.get_param('~port', '/dev/ttyUSB0') |
|
| imu_node.pub = rospy.Publisher(topic, Imu, queue_size=1) |
|
| imu_node.q = quaternion_from_euler(roll,pitch,yaw) |
|
int | imu_node.roll = 0 |
|
int | imu_node.seq = 0 |
|
| imu_node.ser = serial.Serial(port=port, baudrate=57600, timeout=1) |
|
| imu_node.srv = Server(imuConfig, reconfig_callback) |
|
| imu_node.stamp |
|
| imu_node.topic = rospy.get_param('~topic', 'imu') |
|
| imu_node.w |
|
| imu_node.words = line.split(",") |
|
| imu_node.x |
|
| imu_node.y |
|
int | imu_node.yaw = 0 |
|
| imu_node.yaw_deg = -float(words[0]) |
|
| imu_node.z |
|