Skip to content

Commit

Permalink
Fix tons of typos (via lintian -i)
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Aug 23, 2024
1 parent 407ea6b commit 50fd929
Show file tree
Hide file tree
Showing 226 changed files with 439 additions and 441 deletions.
2 changes: 1 addition & 1 deletion 3rdparty/freeglut/freeglut_menu.c
Original file line number Diff line number Diff line change
Expand Up @@ -719,7 +719,7 @@ void fghCalculateMenuBoxSize( void )

/*
* If the entry is a submenu, then it needs to be wider to
* accomodate the arrow. JCJ 31 July 2003
* accommodate the arrow. JCJ 31 July 2003
*/
if (menuEntry->SubMenu )
menuEntry->Width += glutBitmapLength(
Expand Down
2 changes: 1 addition & 1 deletion 3rdparty/xspublic/xscontroller/xsdevice_def.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3702,7 +3702,7 @@ void XsDevice::removeRef()
\param data The data buffer
\param pageNr The page number
\param bankNr The bank number
\returns True if succesful
\returns True if successful
*/
bool XsDevice::writeEmtsPage(uint8_t const* data, int pageNr, int bankNr)
{
Expand Down
6 changes: 3 additions & 3 deletions 3rdparty/xspublic/xstypes/xsfile.c
Original file line number Diff line number Diff line change
Expand Up @@ -312,7 +312,7 @@ XsResultValue XsFile_close(struct XsFile *thisPtr)

/*! \relates XsFile
\brief Writes unwritten data to the file
\returns XRV_OK if the flushing was succesful, an XRV_ERROR otherwise
\returns XRV_OK if the flushing was successful, an XRV_ERROR otherwise
*/
XsResultValue XsFile_flush(struct XsFile *thisPtr)
Expand Down Expand Up @@ -458,7 +458,7 @@ XsResultValue XsFile_puts(struct XsFile *thisPtr, const char *str)
/*! \relates XsFile
\brief Moves the current file position relative to the start of the file
\param offset Position in the file to move to, relative to the start of the file
\returns XRV_OK if the seek was succesful
\returns XRV_OK if the seek was successful
*/
XsResultValue XsFile_seek(struct XsFile *thisPtr, XsFilePos offset)
{
Expand All @@ -472,7 +472,7 @@ XsResultValue XsFile_seek(struct XsFile *thisPtr, XsFilePos offset)
/*! \relates XsFile
\brief Moves the current file position relative to the end of the file
\param offset Position in the file to move to, relative to the end of the file
\returns XRV_OK if the seek was succesful
\returns XRV_OK if the seek was successful
*/
XsResultValue XsFile_seek_r(struct XsFile *thisPtr, XsFilePos offset)
{
Expand Down
2 changes: 1 addition & 1 deletion apps/DifOdometry-Datasets/DifOdometry_Datasets.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -503,7 +503,7 @@ void CDifodoDatasets::loadFrame()
// quat[3] = w, quat[4] = qx; quat[5] = qy; quat[6] = qz;
// gt.setFromXYZQ(quat);

// Set the initial pose (if appropiate)
// Set the initial pose (if appropriate)
if (first_pose == false)
{
cam_pose = gt + transf;
Expand Down
2 changes: 1 addition & 1 deletion apps/SceneViewer3D/_DSceneViewerMain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -820,7 +820,7 @@ void _DSceneViewerFrame::loadFromFile(const std::string& fil, bool isInASequence
const double sceneMaxScale = std::max<double>(1000.0, (sceneBbox.max - sceneBbox.min).norm());
openGLSceneRef->getViewport()->setViewportClipDistances(0.1, 5.0 * sceneMaxScale);

// Change the camera if necesary:
// Change the camera if necessary:
if (openGLSceneRef->followCamera())
{
Viewport::Ptr view = openGLSceneRef->getViewport("main");
Expand Down
2 changes: 1 addition & 1 deletion apps/ro-localization/CPosePDFParticlesExtended.h
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ class CPosePDFParticlesExtended :
*/
~CPosePDFParticlesExtended() override;

/** Copy operator, translating if necesary (for example, between particles
/** Copy operator, translating if necessary (for example, between particles
* and gaussian representations)
*/
void copyFrom(const CPosePDF& o) override;
Expand Down
4 changes: 2 additions & 2 deletions apps/track-video-features/track-video-feats_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -453,7 +453,7 @@ int main(int argc, char** argv)
CImage::setImagesPathBase(CRawlog::detectImagesDirectory(fil));

cam->loadConfig(cfg, "CONFIG");
cam->initialize(); // This will raise an exception if neccesary
cam->initialize(); // This will raise an exception if necessary
}
else
{
Expand All @@ -465,7 +465,7 @@ int main(int argc, char** argv)
cfg.write("CONFIG", "ffmpeg_url", fil);

cam->loadConfig(cfg, "CONFIG");
cam->initialize(); // This will raise an exception if neccesary
cam->initialize(); // This will raise an exception if necessary
}
}

Expand Down
74 changes: 36 additions & 38 deletions doc/mrpt-zeromq-example/main_sub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,52 +19,50 @@ using mrpt::DEG2RAD;

int main()
{
try
{
printf("Subscribing to server...\n");
void* context = zmq_ctx_new();
void* sub_sock = zmq_socket(context, ZMQ_SUB);
int rc = zmq_connect(sub_sock, "tcp://localhost:5555");
assert(rc == 0);
zmq_setsockopt(
sub_sock, ZMQ_SUBSCRIBE, "", 0); // Subscribe to everything.
printf("Subscribed.\n");
try
{
printf("Subscribing to server...\n");
void* context = zmq_ctx_new();
void* sub_sock = zmq_socket(context, ZMQ_SUB);
int rc = zmq_connect(sub_sock, "tcp://localhost:5555");
assert(rc == 0);
zmq_setsockopt(sub_sock, ZMQ_SUBSCRIBE, "", 0); // Subscribe to everything.
printf("Subscribed.\n");

for (int i = 0; i < 10; i++)
{
mrpt::serialization::CSerializable::Ptr obj;
size_t rx_len;
for (int i = 0; i < 10; i++)
{
mrpt::serialization::CSerializable::Ptr obj;
size_t rx_len;

printf("Waiting %d-th incomming pkt...", i);
obj = mrpt::serialization::mrpt_recv_from_zmq(
sub_sock, false /*false:blocking call*/, &rx_len);
if (obj)
{
printf(
"OK!. Type: `%s` (%u bytes)\n",
obj->GetRuntimeClass()->className,
static_cast<unsigned>(rx_len));
}
else
{
printf("failed!\n");
}
printf("Waiting %d-th incoming pkt...", i);
obj =
mrpt::serialization::mrpt_recv_from_zmq(sub_sock, false /*false:blocking call*/, &rx_len);
if (obj)
{
printf(
"OK!. Type: `%s` (%u bytes)\n", obj->GetRuntimeClass()->className,
static_cast<unsigned>(rx_len));
}
else
{
printf("failed!\n");
}

#if 0
// Example for mrpt_recv_from_zmq_into():
mrpt::poses::CPose3D pose;
mrpt_recv_from_zmq_into(sub_sock, pose);
std::cout << "pose: "<< pose << std::endl;
#endif
}
}

zmq_close(sub_sock);
zmq_ctx_destroy(context);
return 0;
}
catch (std::exception& e)
{
std::cerr << "**Exception**: " << e.what() << std::endl;
return -1;
}
zmq_close(sub_sock);
zmq_ctx_destroy(context);
return 0;
}
catch (std::exception& e)
{
std::cerr << "**Exception**: " << e.what() << std::endl;
return -1;
}
}
4 changes: 2 additions & 2 deletions doc/source/doxygen-docs/changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -1257,7 +1257,7 @@
- CICP: parameter `onlyClosestCorrespondences` deleted (always true now).
- mrpt::slam::CICP API: Simplified and modernized to use only one output parameter, using std::optional.
- \ref mrpt_system_grp
- functions to get timestamp as *local* time were removed, since they don't make sense. All timestamps in MRPT are UTC, and they can be formated as dates in either UTC or local time frames.
- functions to get timestamp as *local* time were removed, since they don't make sense. All timestamps in MRPT are UTC, and they can be formatted as dates in either UTC or local time frames.
- Added: mrpt::system::WorkerThreadsPool
- \ref mrpt_rtti_grp [NEW IN MRPT 2.0.0]
- All classes are now registered (and de/serialized) with their full name including namespaces. A backwards-compatible flag has been added to mrpt::rtti::findRegisteredClass().
Expand Down Expand Up @@ -2648,7 +2648,7 @@ href="http://code.google.com/p/mrpt/source/detail?r=3065" >r3065</a>
- New methods mrpt::poses::SE_traits::pseudo_exp()
- mrpt::system::CTimeLogger:
- New method mrpt::system::CTimeLogger::getStats() for
programatic execution time stats analysis - <a
programmatic execution time stats analysis - <a
href="http://code.google.com/p/mrpt/source/detail?r=2998" >r2998</a>
- New method
mrpt::system::CTimeLogger::registerUserMeasure() for making stats of
Expand Down
4 changes: 2 additions & 2 deletions libs/bayes/include/mrpt/bayes/CKalmanFilterCapable_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ void CKalmanFilterCapable<VEH_SIZE, OBS_SIZE, FEAT_SIZE, ACT_SIZE, KFTYPE>::runO
}

// Q is the process noise covariance matrix, is associated to the robot
// movement and is necesary to calculate the prediction P(k+1|k)
// movement and is necessary to calculate the prediction P(k+1|k)
KFMatrix_VxV Q;
OnTransitionNoise(Q);

Expand Down Expand Up @@ -149,7 +149,7 @@ void CKalmanFilterCapable<VEH_SIZE, OBS_SIZE, FEAT_SIZE, ACT_SIZE, KFTYPE>::runO
// =============================================================
for (size_t i = 0; i < VEH_SIZE; i++) m_xkk[i] = xv[i];

// Normalize, if neccesary.
// Normalize, if necessary.
OnNormalizeStateVector();

} // end if (!skipPrediction)
Expand Down
2 changes: 1 addition & 1 deletion libs/bayes/include/mrpt/bayes/CParticleFilterCapable.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ class CParticleFilterCapable
virtual size_t particlesCount() const = 0;

/** Performs the prediction stage of the Particle Filter.
* This method simply selects the appropiate protected method according to
* This method simply selects the appropriate protected method according to
* the particle filter algorithm to run.
* \sa
* prediction_and_update_pfStandardProposal,prediction_and_update_pfAuxiliaryPFStandard,prediction_and_update_pfOptimalProposal,prediction_and_update_pfAuxiliaryPFOptimal
Expand Down
2 changes: 1 addition & 1 deletion libs/bayes/include/mrpt/bayes/CParticleFilterData.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ struct CParticleFilterDataImpl : public CParticleFilterCapable
}

/** Replaces the old particles by copies determined by the indexes in
* "indx", performing an efficient copy of the necesary particles only and
* "indx", performing an efficient copy of the necessary particles only and
* allowing the number of particles to change.*/
void performSubstitution(const std::vector<size_t>& indx) override
{
Expand Down
2 changes: 1 addition & 1 deletion libs/comms/include/mrpt/comms/CSerialPort.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ namespace mrpt::comms
* description, which is platform dependent.
*
* In Windows they are numbered "COM1"-"COM4" and "\\.\COMXXX" for numbers
* above. It is recomended to always use the prefix "\\.\" despite the actual
* above. It is recommended to always use the prefix "\\.\" despite the actual
* port number.
*
* In Linux the name must refer to the device, for example: "ttyUSB0","ttyS0".
Expand Down
2 changes: 1 addition & 1 deletion libs/config/include/mrpt/config/CConfigFile.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ class CConfigFile : public CConfigFileBase
/** Empties the "config file" */
void clear() override;

/** Returs a list with all the keys into a section. */
/** Returns a list with all the keys into a section. */
void getAllKeys(const std::string& section, std::vector<std::string>& keys) const override;

}; // End of class def.
Expand Down
4 changes: 2 additions & 2 deletions libs/config/include/mrpt/config/CConfigFileBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,10 +86,10 @@ class CConfigFileBase
return ret;
}

/** Returs a list with all the keys into a section */
/** Returns a list with all the keys into a section */
virtual void getAllKeys(const std::string& section, std::vector<std::string>& keys) const = 0;

/** Returs, by value, a list with all the keys into a section */
/** Returns, by value, a list with all the keys into a section */
std::vector<std::string> keys(const std::string& section) const
{
std::vector<std::string> keys;
Expand Down
2 changes: 1 addition & 1 deletion libs/config/include/mrpt/config/CConfigFileMemory.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class CConfigFileMemory : public CConfigFileBase

/** Returns a list with all the section names */
void getAllSections(std::vector<std::string>& sections) const override;
/** Returs a list with all the keys into a section */
/** Returns a list with all the keys into a section */
void getAllKeys(const std::string& section, std::vector<std::string>& keys) const override;

private:
Expand Down
6 changes: 3 additions & 3 deletions libs/containers/include/mrpt/containers/CDynamicGrid.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ class CDynamicGrid
const double resolution,
const T* fill_value = nullptr)
{
// Adjust sizes to adapt them to full sized cells acording to the
// Adjust sizes to adapt them to full sized cells according to the
// resolution:
m_x_min = resolution * round(x_min / resolution);
m_y_min = resolution * round(y_min / resolution);
Expand Down Expand Up @@ -121,7 +121,7 @@ class CDynamicGrid
const T& defaultValueNewCells,
double additionalMarginMeters = 2.0)
{
// Is resize really necesary?
// Is resize really necessary?
if (new_x_min >= m_x_min && new_y_min >= m_y_min && new_x_max <= m_x_max &&
new_y_max <= m_y_max)
return;
Expand All @@ -140,7 +140,7 @@ class CDynamicGrid
if (new_y_max > m_y_max) new_y_max = ceil(new_y_max + additionalMarginMeters);
}

// Adjust sizes to adapt them to full sized cells acording to the
// Adjust sizes to adapt them to full sized cells according to the
// resolution:
if (fabs(new_x_min / m_resolution - round(new_x_min / m_resolution)) > 0.05f)
new_x_min = m_resolution * round(new_x_min / m_resolution);
Expand Down
10 changes: 5 additions & 5 deletions libs/containers/include/mrpt/containers/CDynamicGrid3D.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class CDynamicGrid3D
const T& defaultValueNewCells,
coord_t additionalMarginMeters = 2)
{
// Is resize really necesary?
// Is resize really necessary?
if (new_x_min >= m_x_min && new_y_min >= m_y_min && new_z_min >= m_z_min &&
new_x_max <= m_x_max && new_y_max <= m_y_max && new_z_max <= m_z_max)
return;
Expand All @@ -82,7 +82,7 @@ class CDynamicGrid3D
if (new_z_max > m_z_max) new_z_max = ceil(new_z_max + additionalMarginMeters);
}

// Adjust sizes to adapt them to full sized cells acording to the
// Adjust sizes to adapt them to full sized cells according to the
// resolution:
if (fabs(new_x_min / m_resolution_xy - round(new_x_min / m_resolution_xy)) > 0.05)
new_x_min = m_resolution_xy * round(new_x_min / m_resolution_xy);
Expand Down Expand Up @@ -171,7 +171,7 @@ class CDynamicGrid3D
{
const coord_t resolution_z = resolution_z_ > 0 ? resolution_z_ : resolution_xy;

// Adjust sizes to adapt them to full sized cells acording to the
// Adjust sizes to adapt them to full sized cells according to the
// resolution:
m_x_min = x_min;
m_y_min = y_min;
Expand Down Expand Up @@ -338,7 +338,7 @@ class CDynamicGrid3D

public:
/** Serialization of all parameters, except the contents of each voxel
* (responsability of the derived class) */
* (responsibility of the derived class) */
template <class ARCHIVE>
void dyngridcommon_writeToStream(ARCHIVE& out) const
{
Expand All @@ -349,7 +349,7 @@ class CDynamicGrid3D
.template WriteAs<uint32_t>(m_size_z);
}
/** Serialization of all parameters, except the contents of each voxel
* (responsability of the derived class) */
* (responsibility of the derived class) */
template <class ARCHIVE>
void dyngridcommon_readFromStream(ARCHIVE& in)
{
Expand Down
2 changes: 1 addition & 1 deletion libs/graphs/include/mrpt/graphs/ScalarFactorGraph.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class ScalarFactorGraph : public mrpt::system::COutputLogger
/** Insert constraints into the GMRF problem.
* \param listOfConstraints List of user-implemented constraints.
* **A pointer to the passed object is kept**, but memory ownship *REMAINS*
* being responsability of the caller. This is
* being responsibility of the caller. This is
* done such that arrays/vectors of constraints can be more efficiently
* allocated if their type is known at build time.
*/
Expand Down
2 changes: 1 addition & 1 deletion libs/graphs/src/CGraphPartitioner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@ void CGraphPartitioner<GRAPH_MATRIX, num_t>::exactBisection(
else
Adj = in_A;

// Brute force: compute all posible partitions:
// Brute force: compute all possible partitions:
//-----------------------------------------------------------------

// First combination: 1000...0000
Expand Down
4 changes: 2 additions & 2 deletions libs/graphslam/include/mrpt/graphslam/CGraphSlamEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -280,7 +280,7 @@ class CGraphSlamEngine : public mrpt::system::COutputLogger
/**\brief Main class method responsible for parsing each measurement and
* for executing graphSLAM.
*
* \note Method reads each measurement seperately, so the application that
* \note Method reads each measurement separately, so the application that
* invokes it is responsibe for fetching the measurements (e.g. from a
* rawlog file).
*
Expand Down Expand Up @@ -738,7 +738,7 @@ class CGraphSlamEngine : public mrpt::system::COutputLogger
* \brief Flags for visualizing various trajectories/objects of interest.
*
* These are set from the .ini configuration file. The actual visualization
* of these objects can be overriden if the user issues the corresponding
* of these objects can be overridden if the user issues the corresponding
* keystrokes in the CDisplayWindow3D. In order for them to have any
* effect, a pointer to CDisplayWindow3D has to be given first.
*/
Expand Down
4 changes: 2 additions & 2 deletions libs/graphslam/include/mrpt/graphslam/CGraphSlamEngine_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -528,7 +528,7 @@ bool CGraphSlamEngine<GRAPH_T>::_execGraphSlamStep(
m_last_laser_scan2D = scan;

if (!m_first_laser_scan2D)
{ // capture first laser scan seperately
{ // capture first laser scan separately
m_first_laser_scan2D = m_last_laser_scan2D;
}
}
Expand Down Expand Up @@ -1377,7 +1377,7 @@ void CGraphSlamEngine<GRAPH_T>::readGTFileRGBD_TUM(
}
}

// handle the first pose seperately
// handle the first pose separately
// make sure that the ground-truth starts at 0.
pose_t pose_diff;
vector<string> curr_tokens;
Expand Down
Loading

0 comments on commit 50fd929

Please sign in to comment.