Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <string>
00041 #include <vector>
00042
00043
00044 #include <ros/ros.h>
00045
00046
00047 #include <rosparam_shortcuts/rosparam_shortcuts.h>
00048
00049 int main(int argc, char** argv)
00050 {
00051 std::string name = "example";
00052 ros::init(argc, argv, name);
00053 ros::NodeHandle nh;
00054 ROS_INFO_STREAM_NAMED(name, "Starting rosparam shortcuts example...");
00055
00056
00057 ros::AsyncSpinner spinner(2);
00058 spinner.start();
00059
00060 double control_rate;
00061 int param1;
00062 std::size_t param2;
00063 ros::Duration param3;
00064 Eigen::Affine3d param4;
00065 std::vector<double> param5;
00066
00067
00068 ros::NodeHandle rpnh(nh, name);
00069 std::size_t error = 0;
00070 error += !rosparam_shortcuts::get(name, rpnh, "control_rate", control_rate);
00071 error += !rosparam_shortcuts::get(name, rpnh, "param1", param1);
00072 error += !rosparam_shortcuts::get(name, rpnh, "param2", param2);
00073 error += !rosparam_shortcuts::get(name, rpnh, "param3", param3);
00074 error += !rosparam_shortcuts::get(name, rpnh, "param4", param4);
00075 error += !rosparam_shortcuts::get(name, rpnh, "param5", param5);
00076
00077 rosparam_shortcuts::shutdownIfError(name, error);
00078
00079
00080 ROS_INFO_STREAM_NAMED(name, "control rate: " << control_rate);
00081 ROS_INFO_STREAM_NAMED(name, "param1: " << param1);
00082 ROS_INFO_STREAM_NAMED(name, "param2: " << param2);
00083 ROS_INFO_STREAM_NAMED(name, "param3: " << param3.toSec());
00084 ROS_INFO_STREAM_NAMED(name, "param4: Translation:\n" << param4.translation());
00085 ROS_INFO_STREAM_NAMED(name, "param5[0]: " << param5[0]);
00086 ROS_INFO_STREAM_NAMED(name, "param5[3]: " << param5[3]);
00087 ROS_INFO_STREAM_NAMED(name, "Shutting down.");
00088 ros::shutdown();
00089
00090 return 0;
00091 }