Go to the documentation of this file.
23 #include <boost/thread/recursive_mutex.hpp>
26 #include <geometry_msgs/Twist.h>
27 #include <sensor_msgs/Imu.h>
28 #include <sensor_msgs/LaserScan.h>
29 #include <nav_msgs/Odometry.h>
32 #define PI 3.14159265359
88 nh.
param<
double>(
"base_controller/track_width", odom, 0.37476);
89 nh.
param<
double>(
"imu/gyro/scale", imu, 0.001221729);
92 double odom_scale = 0.0;
93 double imu_scale = 0.0;
96 for (
size_t i = 0; i <
scan_.size(); ++i)
102 odom_scale /=
scan_.size();
103 imu_scale /=
scan_.size();
105 std::stringstream ss;
106 ss <<
"odom: " << odom * (1.0 + odom_scale) << std::endl;
107 ss <<
"imu: " << imu * (1.0 + imu_scale) << std::endl;
120 std::cout <<
"aligning..." << std::endl;
151 std::cout <<
"...done" << std::endl;
164 std::cout <<
"spin..." << std::endl;
189 std::cout <<
"...done" << std::endl;
211 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
221 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
231 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
233 double angle = scan->angle_min;
234 double mean_x, mean_y, n;
235 mean_x = mean_y = n = 0;
237 for (
size_t i = 0; i < scan->ranges.size(); ++i,
angle += scan->angle_increment)
244 if (std::isnan(scan->ranges[i]))
255 double px = sin(
angle) * scan->ranges[i];
256 double py = cos(
angle) * scan->ranges[i];
271 angle = scan->angle_min +
start * scan->angle_increment;
272 double x,
y, xx, xy, yy;
273 x =
y = xx = xy = yy = n = 0;
274 for (
size_t i =
start; i < scan->ranges.size(); ++i,
angle += scan->angle_increment)
281 if (std::isnan(scan->ranges[i]))
287 double px = sin(
angle) * scan->ranges[i] - mean_x;
288 double py = cos(
angle) * scan->ranges[i] - mean_y;
308 geometry_msgs::Twist twist;
309 twist.angular.z = vel;
315 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
std::string print()
Print out current calibration state.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ros::Subscriber imu_subscriber_
std::string printCalibrationData()
Print out the calibration data.
boost::recursive_mutex data_mutex_
ROSCPP_DECL void spinOnce()
bool align(double angle, bool verbose=false)
Align to the wall.
bool spin(double velocity, int rotations, bool verbose=false)
Spin and record imu, odom, scan.
std::vector< double > imu_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void sendVelocityCommand(double vel)
Send a rotational velocity command.
ros::Time last_imu_stamp_
std::vector< double > odom_
ros::Subscriber scan_subscriber_
void laserCallback(const sensor_msgs::LaserScan::Ptr &scan)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void imuCallback(const sensor_msgs::Imu::Ptr &imu)
BaseCalibration(ros::NodeHandle &n)
Create a base calibration instance.
ros::Subscriber odom_subscriber_
void odometryCallback(const nav_msgs::Odometry::Ptr &odom)
std::vector< double > scan_
Calibration code lives under this namespace.
T param(const std::string ¶m_name, const T &default_val) const
ros::Time last_scan_stamp_
ros::Time last_odom_stamp_
void clearMessages()
Clear any received messages.
void resetInternal()
Reset the odom/imu counters.
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01