Macros
assert.h File Reference
#include "ros/console.h"
#include "ros/static_assert.h"
#include <ros/platform.h>
#include <stdlib.h>
Include dependency graph for assert.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Macros

#define ROS_ASSERT(cond)
 Asserts that the provided condition evaluates to true. More...
 
#define ROS_ASSERT_CMD(cond, cmd)
 Runs a command if the provided condition is false. More...
 
#define ROS_ASSERT_ENABLED
 
#define ROS_ASSERT_MSG(cond, ...)
 Asserts that the provided condition evaluates to true. More...
 
#define ROS_BREAK()
 Aborts program execution. More...
 
#define ROS_ISSUE_BREAK()   abort();
 Always issues a breakpoint instruction. More...
 

Macro Definition Documentation

◆ ROS_ASSERT

#define ROS_ASSERT (   cond)
Value:
do { \
if (!(cond)) { \
ROS_FATAL("ASSERTION FAILED\n\tfile = %s\n\tline = %d\n\tcond = %s\n", __FILE__, __LINE__, #cond); \
ROS_ISSUE_BREAK() \
} \
} while (false)

Asserts that the provided condition evaluates to true.

If it is false, program execution will abort, with an informative statement about which assertion failed, in what file. Use ROS_ASSERT instead of assert() itself.

If running inside a debugger, ROS_ASSERT will allow you to step past the assertion.

Definition at line 120 of file assert.h.

◆ ROS_ASSERT_CMD

#define ROS_ASSERT_CMD (   cond,
  cmd 
)
Value:
do { \
if (!(cond)) { \
cmd; \
} \
} while (false)

Runs a command if the provided condition is false.

For example:

  ROS_ASSERT_CMD(x > 0, handleError(...));

Definition at line 138 of file assert.h.

◆ ROS_ASSERT_ENABLED

#define ROS_ASSERT_ENABLED

Definition at line 109 of file assert.h.

◆ ROS_ASSERT_MSG

#define ROS_ASSERT_MSG (   cond,
  ... 
)
Value:
do { \
if (!(cond)) { \
ROS_FATAL("ASSERTION FAILED\n\tfile = %s\n\tline = %d\n\tcond = %s\n\tmessage = ", __FILE__, __LINE__, #cond); \
ROS_FATAL(__VA_ARGS__); \
ROS_FATAL("\n"); \
ROS_ISSUE_BREAK(); \
} \
} while (false)

Asserts that the provided condition evaluates to true.

If it is false, program execution will abort, with an informative statement about which assertion failed, in what file, and it will print out a printf-style message you define. Example usage:

  ROS_ASSERT_MSG(x > 0, "Uh oh, x went negative.  Value = %d", x);

If running inside a debugger, ROS_ASSERT will allow you to step past the assertion.

Definition at line 128 of file assert.h.

◆ ROS_BREAK

#define ROS_BREAK ( )
Value:
do { \
ROS_FATAL("BREAKPOINT HIT\n\tfile = %s\n\tline=%d\n", __FILE__, __LINE__); \
ROS_ISSUE_BREAK() \
} while (false)

Aborts program execution.

Aborts program execution with an informative message stating what file and line it was called from. Use ROS_BREAK instead of calling assert(0) or ROS_ASSERT(0).

If running inside a debugger, ROS_BREAK will allow you to step past the breakpoint.

Definition at line 114 of file assert.h.

◆ ROS_ISSUE_BREAK

#define ROS_ISSUE_BREAK ( )    abort();

Always issues a breakpoint instruction.

This define is mostly for internal use, but is useful if you want to simply issue a break instruction in a cross-platform way.

Currently implemented for Windows (any platform), powerpc64, and x86

Definition at line 104 of file assert.h.



rosconsole
Author(s): Josh Faust
autogenerated on Wed Mar 2 2022 00:53:52