40 #include <geometry_msgs/Twist.h> 41 #include <nav_msgs/Path.h> 64 void cbPath(
const nav_msgs::Path::ConstPtr& msg);
97 ROS_INFO(
"Size: %d\n", (
int)serial_size);
103 ofs.write(reinterpret_cast<char*>(buffer.get()), serial_size);
123 int main(
int argc,
char** argv)
125 ros::init(argc, argv,
"trajectory_saver");
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber sub_path_
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
int main(int argc, char **argv)
void serialize(Stream &stream, const T &t)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void cbPath(const nav_msgs::Path::ConstPtr &msg)
uint32_t serializationLength(const T &t)
ROSCPP_DECL void spinOnce()
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T ¶m, const T &default_value)