diff --git a/README.md b/README.md index 6fd7873..2e5e5cd 100644 --- a/README.md +++ b/README.md @@ -28,6 +28,10 @@ Build the package in your workspace: Source setup.bash in your workspace: . install/setup.bash + +Grant user access to i2c, need to reboot afterwards: + + sudo usermod -aG i2c Launch it: diff --git a/params/mpu6050.yaml b/params/mpu6050.yaml index 38838f8..6372039 100644 --- a/params/mpu6050.yaml +++ b/params/mpu6050.yaml @@ -14,4 +14,4 @@ mpu6050driver_node: accel_x_offset: 0.0 # [m/s²] accel_y_offset: 0.0 # [m/s²] accel_z_offset: 0.0 # [m/s²] - frequency: 100 # [Hz] + frequency: 50 # [Hz] diff --git a/src/mpu6050driver.cpp b/src/mpu6050driver.cpp index 541afd4..15c4014 100644 --- a/src/mpu6050driver.cpp +++ b/src/mpu6050driver.cpp @@ -33,7 +33,7 @@ MPU6050Driver::MPU6050Driver() // Create publisher publisher_ = this->create_publisher("imu", 10); std::chrono::duration frequency = - 1000ms / this->get_parameter("gyro_range").as_int(); + 1000ms / this->get_parameter("frequency").as_int(); timer_ = this->create_wall_timer(frequency, std::bind(&MPU6050Driver::handleInput, this)); } @@ -41,15 +41,16 @@ void MPU6050Driver::handleInput() { auto message = sensor_msgs::msg::Imu(); message.header.stamp = this->get_clock()->now(); - message.header.frame_id = "base_link"; + message.header.frame_id = "imu"; //"base_link"; message.linear_acceleration_covariance = {0}; message.linear_acceleration.x = mpu6050_->getAccelerationX(); message.linear_acceleration.y = mpu6050_->getAccelerationY(); message.linear_acceleration.z = mpu6050_->getAccelerationZ(); message.angular_velocity_covariance[0] = {0}; - message.angular_velocity.x = mpu6050_->getAngularVelocityX(); - message.angular_velocity.y = mpu6050_->getAngularVelocityY(); - message.angular_velocity.z = mpu6050_->getAngularVelocityZ(); + float deg_to_rad = 0.0174533; + message.angular_velocity.x = mpu6050_->getAngularVelocityX()*deg_to_rad; + message.angular_velocity.y = mpu6050_->getAngularVelocityY()*deg_to_rad; + message.angular_velocity.z = mpu6050_->getAngularVelocityZ()*deg_to_rad; // Invalidate quaternion message.orientation_covariance[0] = -1; message.orientation.x = 0; @@ -80,4 +81,4 @@ int main(int argc, char* argv[]) rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; -} \ No newline at end of file +}