diff --git a/img_dev/CMakeLists.txt b/img_dev/CMakeLists.txt index 5a25de0..348f8cb 100644 --- a/img_dev/CMakeLists.txt +++ b/img_dev/CMakeLists.txt @@ -34,7 +34,7 @@ target_link_libraries(img_dev_node ament_target_dependencies(img_dev_node rclcpp sensor_msgs realsense2_camera_msgs interfaces) install(TARGETS img_dev_node DESTINATION lib/${PROJECT_NAME}) -install(DIRECTORY msg/ DESTINATION share/${PROJECT_NAME}) +# install(DIRECTORY msg/ DESTINATION share/${PROJECT_NAME}) install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch}) ament_export_dependencies(rosidl_default_runtime) diff --git a/input_dev/CMakeLists.txt b/input_dev/CMakeLists.txt index 2f3aeaa..6bc7441 100644 --- a/input_dev/CMakeLists.txt +++ b/input_dev/CMakeLists.txt @@ -44,6 +44,6 @@ target_link_libraries(input_dev_node ament_target_dependencies(input_dev_node rclcpp sensor_msgs interfaces) install(TARGETS input_dev_node DESTINATION lib/${PROJECT_NAME}) -install(DIRECTORY msg/ DESTINATION share/${PROJECT_NAME}) +#install(DIRECTORY msg/ DESTINATION share/${PROJECT_NAME}) install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch) ament_package() diff --git a/motor_dev/src/main.cpp b/motor_dev/src/main.cpp index dc652fa..575de29 100644 --- a/motor_dev/src/main.cpp +++ b/motor_dev/src/main.cpp @@ -7,6 +7,31 @@ using namespace motor_dev; RS485Driver rs485_driver_; +static auto g_program_start_time = std::chrono::steady_clock::now(); + +// 带时间戳的 printf 风格日志函数 +void log_printf(const char* format, ...) { + auto now = std::chrono::steady_clock::now(); + auto elapsed = std::chrono::duration_cast>(now - g_program_start_time); + double seconds = elapsed.count(); + + char buffer[1024]; + va_list args; + va_start(args, format); + int n = vsnprintf(buffer, sizeof(buffer), format, args); + va_end(args); + + if (n < 0) { + std::fprintf(stderr, "[%.3f] (log error)\n", seconds); + return; + } + + std::fprintf(stdout, "[%.3f] %s\n", seconds, buffer); + std::fflush(stdout); // 确保立即输出(对调试很重要) +} + + + int main(int argc,char* argv[]){ rclcpp::init(argc,argv); auto node=rclcpp::Node::make_shared("motor_dev_node"); @@ -24,13 +49,13 @@ int main(int argc,char* argv[]){ rs485_driver_.bm_set_mode(2,4); rs485_driver_.bm_set_enable(2,2); - //rs485_driver_.bm_set_param(1,77,10); - //rs485_driver_.bm_set_param(1,78,2); - //rs485_driver_.bm_set_param(1,79,2); + rs485_driver_.bm_set_param(1,77,15); + rs485_driver_.bm_set_param(1,78,4); + rs485_driver_.bm_set_param(1,79,4); //rs485_driver_.bm_set_param(1,28,4); - rs485_driver_.bm_set_param(2,77,10); - rs485_driver_.bm_set_param(2,78,2); - rs485_driver_.bm_set_param(2,79,2); + rs485_driver_.bm_set_param(2,77,15); + rs485_driver_.bm_set_param(2,78,4); + rs485_driver_.bm_set_param(2,79,4); //rs485_driver_.mt_set_pos(1,-5); //init /////rs485_driver_.bm_set_mode(1,3);//位置模式 @@ -49,8 +74,8 @@ int main(int argc,char* argv[]){ // float speed1=msg->motor_speed[0]; //float speed2=msg->motor_speed[1]; - printf("####vvv##########:%s,speed:%.1f,%.1f\n",msg->type.c_str(),angle1,angle2); - ////rs485_driver_.bm_set_pos(angle1,angle2); + log_printf("recv topic:%s,angle:%.1f,%.1f",msg->type.c_str(),angle1,angle2); + rs485_driver_.bm_set_pos(angle1,angle2); // rs485_driver_.bm_set_speed(speed1,speed2); }else if(msg->type=="mt"){ uint8_t id=msg->motor_id[0]; @@ -61,11 +86,12 @@ int main(int argc,char* argv[]){ //TODO } }); -#if 0 +#if 1 auto motor_pub=node->create_publisher("/motor_pos",10); //读取电机位置 rclcpp::TimerBase::SharedPtr timer_=node->create_wall_timer(std::chrono::milliseconds(2000), [=]() { static int pub_cnt=0; + log_printf("query motor pos"); interfaces::msg::MotorPos motor_pos; float angle1=rs485_driver_.bm_get_pos(1); float angle2=rs485_driver_.bm_get_pos(2); @@ -93,7 +119,7 @@ int main(int argc,char* argv[]){ motor_pub->publish(motor_pos); //std::cout<<"pub msg["<create_service("motor_param",[=](const std::shared_ptr req,std::shared_ptr res){ uint8_t mid=req->motor_id; res->ret=-1; - printf("recv sv:%d,%d,%d,%d\n",req->motor_id,req->max_speed,req->add_acc,req->dec_acc); - if(mid>-1&&mid<500){ + log_printf("recv sv:%d,%d,%d,%d",req->motor_id,req->max_speed,req->add_acc,req->dec_acc); + //if(mid>-1&&mid<500) + { if(req->max_speed<500&&req->add_acc<500&&req->dec_acc<500){ rs485_driver_.bm_set_param(mid,77,req->max_speed); rs485_driver_.bm_set_param(mid,78,req->add_acc); @@ -123,6 +150,7 @@ int main(int argc,char* argv[]){ } } }); +#if 0 auto motor_info_srv=node->create_service("motor_info",[=](const std::shared_ptr req,std::shared_ptr res){ printf("recv motor_info:%s,%d\n",req->type.c_str(),req->motor_ids[0]); res->ret=false; @@ -137,7 +165,7 @@ auto motor_info_srv=node->create_service("motor_info } }); - +#endif rclcpp::spin(node); printf("now close rs485 port\n");