Go to the documentation of this file.
34 #include <boost/function.hpp>
35 #include <boost/bind/placeholders.hpp>
45 ROS_INFO(
"Starting initialization timer...");
91 std::vector<std::pair<std::string, int> > enums;
92 enums.push_back({
"First", 1});
93 enums.push_back({
"Second", 2});
94 enums.push_back({
"Third", 3});
95 enums.push_back({
"Zeroth", 0});
120 int main(
int argc,
char **argv)
122 ros::init(argc, argv,
"dynamic_parameters_test");
DynamicParametersTestNode()
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
double getTestDouble() const
float getTestFloat() const
const std::string & getTestEnum() const
void addEnums(const std::string ¶m, const std::vector< std::pair< std::string, int > > &enums)
void get(const std::string &name, float &variable, const float default_value, const std::string description="None.", const float min=-100, const float max=100)
const std::string & getTestString() const
void finalize(bool alphabetical_order=true)
void handleReconfigure(swri::DynamicParameters ¶ms)
void initialize(ros::NodeHandle &pnh)
void setCallback(boost::function< void(DynamicParameters &)> fun)
int main(int argc, char **argv)
ros::WallTimer init_timer_
swri::DynamicParameters params_
void initialize(const ros::WallTimerEvent &)
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
swri_roscpp
Author(s): P. J. Reed
autogenerated on Fri Aug 2 2024 08:39:15