Sanitize node memory consumption with a smaller TF buffer size. (#879)
Fixes an (almost) unbounded growth of the TF buffer. See the heap profile logs in the PR for more information.master
parent
4ecf04b49f
commit
d53d339562
|
@ -45,7 +45,7 @@ namespace cartographer_ros {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
void Run() {
|
void Run() {
|
||||||
constexpr double kTfBufferCacheTimeInSeconds = 1e6;
|
constexpr double kTfBufferCacheTimeInSeconds = 10.;
|
||||||
tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
|
tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
|
||||||
tf2_ros::TransformListener tf(tf_buffer);
|
tf2_ros::TransformListener tf(tf_buffer);
|
||||||
NodeOptions node_options;
|
NodeOptions node_options;
|
||||||
|
|
|
@ -44,7 +44,7 @@ namespace cartographer_ros {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
void Run() {
|
void Run() {
|
||||||
constexpr double kTfBufferCacheTimeInSeconds = 1e6;
|
constexpr double kTfBufferCacheTimeInSeconds = 10.;
|
||||||
tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
|
tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
|
||||||
tf2_ros::TransformListener tf(tf_buffer);
|
tf2_ros::TransformListener tf(tf_buffer);
|
||||||
NodeOptions node_options;
|
NodeOptions node_options;
|
||||||
|
|
Loading…
Reference in New Issue