Skip to content

Commit

Permalink
removed -1 in covariance matrix and changed acc covariance
Browse files Browse the repository at this point in the history
  • Loading branch information
Beluga Xavier committed Mar 12, 2022
1 parent b462e10 commit b784d16
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions src/stim300_driver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,14 +76,14 @@ int main(int argc, char** argv)
int sample_rate{ 0 };
double gravity{ 0 };


node.param<std::string>("device_name", device_name, "/dev/ttyUSB0");
node.param("variance_gyro", variance_gyro,0.0001*2*4.6*pow(10,-4));
node.param("variance_acc", variance_acc, 4.0);
node.param("variance_acc", variance_acc, 0.000055);
node.param("sample_rate", sample_rate, 125);
node.param("gravity", gravity, 9.80665);

sensor_msgs::Imu stim300msg{};
stim300msg.orientation_covariance[0] = -1;
stim300msg.angular_velocity_covariance[0] = variance_gyro;
stim300msg.angular_velocity_covariance[4] = variance_gyro;
stim300msg.angular_velocity_covariance[8] = variance_gyro;
Expand Down Expand Up @@ -203,9 +203,9 @@ int main(int argc, char** argv)
// Acceleration wild point filter

// Previous message
acceleration_buffer_x.push_back(driver_stim300.getAccX * gravity);
acceleration_buffer_y.push_back(driver_stim300.getAccY * gravity);
acceleration_buffer_z.push_back(driver_stim300.getAccZ * gravity);
acceleration_buffer_x.push_back(driver_stim300.getAccX() * gravity);
acceleration_buffer_y.push_back(driver_stim300.getAccY() * gravity);
acceleration_buffer_z.push_back(driver_stim300.getAccZ() * gravity);
stim300msg.header.stamp = ros::Time::now();

if (acceleration_buffer_x.size() == 2 && acceleration_buffer_y.size() == 2 && acceleration_buffer_z.size() == 2)
Expand Down

0 comments on commit b784d16

Please sign in to comment.