diff --git a/crosbot_explore/src/explorer.cpp b/crosbot_explore/src/explorer.cpp index 2d58e5da8dad930f69cfb9013a2af92745ac46ab..78833c4538cb900b0472a776299e18eb0cdecbde 100644 --- a/crosbot_explore/src/explorer.cpp +++ b/crosbot_explore/src/explorer.cpp @@ -8,6 +8,8 @@ #include #include +#include + namespace crosbot { #define DEFAULT_SLEEP_TIME 50000 diff --git a/crosbot_fastslam/include/crosbot_fastslam/serialization.hpp b/crosbot_fastslam/include/crosbot_fastslam/serialization.hpp index 32e15435d1f2f63533b9cff83d3b5eafed424969..a4b2b3f6f3ed591b780d196b9c9abe49288e6886 100644 --- a/crosbot_fastslam/include/crosbot_fastslam/serialization.hpp +++ b/crosbot_fastslam/include/crosbot_fastslam/serialization.hpp @@ -167,7 +167,7 @@ public: uint32_t nonNulls = 0; rval += serUInt32.read(nonNulls, stream); - for (uint32_t i = 0; i < nonNulls; i++) { + for (uint32_t n = 0; n < nonNulls; n++) { uint32_t i, j; rval += serUInt32.read(i, stream); rval += serUInt32.read(j, stream); diff --git a/crosbot_fastslam/src/fastslam.cpp b/crosbot_fastslam/src/fastslam.cpp index 840fd63f2604e3e37f424c404810b4e183761d57..0874e55da6236c4b6d65eafc0fa40558720bee5d 100644 --- a/crosbot_fastslam/src/fastslam.cpp +++ b/crosbot_fastslam/src/fastslam.cpp @@ -78,7 +78,7 @@ void FastSLAMMap::configure(ConfigElementPtr config) { parameters.searchPose = searchConfig->getParamAsPose("pose", parameters.searchPose); } - parameters.addMotionCopy = searchConfig->getParamAsBool("add_motion_copy", parameters.addMotionCopy); + parameters.addMotionCopy = config->getParamAsBool("add_motion_copy", parameters.addMotionCopy); } void FastSLAMMap::start() { diff --git a/crosbot_ui/src/joystick.cpp b/crosbot_ui/src/joystick.cpp index 581caa99930439b0893fadf3f5f94f467b745bec..f90e41ffbfe688c71d2f605886e09ae0553cc3fe 100644 --- a/crosbot_ui/src/joystick.cpp +++ b/crosbot_ui/src/joystick.cpp @@ -11,6 +11,8 @@ #include #include #include +#include +#include namespace crosbot {