jiting
This commit is contained in:
		
							parent
							
								
									053643c1c4
								
							
						
					
					
						commit
						1384f86fe3
					
				@ -88,11 +88,11 @@ catkin_package(
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
add_executable(fastlio_mapping1 src/laserMapping.cpp include/ikd-Tree/ikd_Tree.cpp src/preprocess.cpp)
 | 
					add_executable(fastlio_mapping1 src/laserMapping.cpp include/ikd-Tree/ikd_Tree.cpp src/preprocess.cpp)
 | 
				
			||||||
add_executable(flag src/flag.cpp)
 | 
					add_executable(flag src/flag.cpp)
 | 
				
			||||||
add_executable(send src/send.cpp src/mbot_linux_serial.cpp)
 | 
					add_executable(controlpid src/controlpid.cpp src/mbot_linux_serial.cpp)
 | 
				
			||||||
target_link_libraries(fastlio_mapping1 ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES})
 | 
					target_link_libraries(fastlio_mapping1 ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES})
 | 
				
			||||||
target_link_libraries(flag ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES})
 | 
					target_link_libraries(flag ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES})
 | 
				
			||||||
target_link_libraries(send ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES})
 | 
					target_link_libraries(controlpid ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES})
 | 
				
			||||||
target_include_directories(fastlio_mapping1 PRIVATE ${PYTHON_INCLUDE_DIRS})
 | 
					target_include_directories(fastlio_mapping1 PRIVATE ${PYTHON_INCLUDE_DIRS})
 | 
				
			||||||
target_include_directories(flag PRIVATE ${PYTHON_INCLUDE_DIRS})
 | 
					target_include_directories(flag PRIVATE ${PYTHON_INCLUDE_DIRS})
 | 
				
			||||||
target_include_directories(send PRIVATE ${PYTHON_INCLUDE_DIRS})
 | 
					target_include_directories(controlpid PRIVATE ${PYTHON_INCLUDE_DIRS})
 | 
				
			||||||
add_dependencies(fastlio_mapping fast_lio_generate_messages_cpp)
 | 
					add_dependencies(fastlio_mapping fast_lio_generate_messages_cpp)
 | 
				
			||||||
 | 
				
			|||||||
@ -1,4 +1,4 @@
 | 
				
			|||||||
image: /home/cmrt/mid360/ws_livox/src/FAST_LIO_LOCALIZATION/PCD/M3.pgm
 | 
					image: /home/cmrt/ws_livox/src/FAST_LIO_LOCALIZATION/PCD/M3.pgm
 | 
				
			||||||
resolution: 0.050000
 | 
					resolution: 0.050000
 | 
				
			||||||
origin: [-18.653002, -10.328159, 0.000000]
 | 
					origin: [-18.653002, -10.328159, 0.000000]
 | 
				
			||||||
negate: 0
 | 
					negate: 0
 | 
				
			||||||
 | 
				
			|||||||
@ -16,7 +16,7 @@
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
	<!-- <arg name="map" default="/home/rm/ws_sentry/src/FAST_LIO/PCD(305_10-20)/scans.pcd" /> -->
 | 
						<!-- <arg name="map" default="/home/rm/ws_sentry/src/FAST_LIO/PCD(305_10-20)/scans.pcd" /> -->
 | 
				
			||||||
	<arg name="map" default="$(find fast_lio)/PCD/scans.pcd" />
 | 
						<arg name="map" default="$(find fast_lio_localization)/PCD/scans.pcd" />
 | 
				
			||||||
	<!-- loalization-->
 | 
						<!-- loalization-->
 | 
				
			||||||
    <node pkg="fast_lio_localization" type="global_localization.py" name="global_localization" output="screen" />
 | 
					    <node pkg="fast_lio_localization" type="global_localization.py" name="global_localization" output="screen" />
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
				
			|||||||
@ -47,7 +47,7 @@ public:
 | 
				
			|||||||
            {2.981, 1.60, -M_PI/2},
 | 
					            {2.981, 1.60, -M_PI/2},
 | 
				
			||||||
        };
 | 
					        };
 | 
				
			||||||
        target_ = target_poses_[0];
 | 
					        target_ = target_poses_[0];
 | 
				
			||||||
 | 
					        laser_sub = nh_.subscribe<sensor_msgs::LaserScan>("/scan", 10, &PoseController::laser_callback, this);
 | 
				
			||||||
        pose_subscriber_ = nh_.subscribe("filtered_pose", 10, &PoseController::pose_callback, this);
 | 
					        pose_subscriber_ = nh_.subscribe("filtered_pose", 10, &PoseController::pose_callback, this);
 | 
				
			||||||
        cmd_pid_publisher_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel_pid", 10);
 | 
					        cmd_pid_publisher_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel_pid", 10);
 | 
				
			||||||
        //position_id_subscriber_ = nh_.subscribe("/position_id", 10, &PoseController::position_id_callback, this);
 | 
					        //position_id_subscriber_ = nh_.subscribe("/position_id", 10, &PoseController::position_id_callback, this);
 | 
				
			||||||
@ -131,9 +131,44 @@ private:
 | 
				
			|||||||
        cmd.angular.z = control_yaw;
 | 
					        cmd.angular.z = control_yaw;
 | 
				
			||||||
        cmd_pid_publisher_.publish(cmd);//发送pid
 | 
					        cmd_pid_publisher_.publish(cmd);//发送pid
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
 | 
					    //发送
 | 
				
			||||||
    void serial_write3double_callback(const geometry_msgs::Twist::ConstPtr& msg) {
 | 
					    void serial_write3double_callback(const geometry_msgs::Twist::ConstPtr& msg) {
 | 
				
			||||||
        write3float(msg->linear.x, msg->linear.y, msg->angular.z);
 | 
					        //write3float(msg->linear.x, msg->linear.y, msg->angular.z);
 | 
				
			||||||
 | 
					        write3float2(msg->linear.x, msg->linear.y, msg->angular.z);//lzcdxc
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    //避障
 | 
				
			||||||
 | 
					    void laser_callback(const sensor_msgs::LaserScan::ConstPtr& msg) {
 | 
				
			||||||
 | 
					    static const float min_distance = 0.45; // 最小安全距离,单位:米
 | 
				
			||||||
 | 
					    bool obstacle_detected = false;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    for (size_t i = 0; i < msg->ranges.size(); i=i+30) {
 | 
				
			||||||
 | 
					        float distance = msg->ranges[i];
 | 
				
			||||||
 | 
					        if (distance < min_distance && !std::isnan(distance)) {
 | 
				
			||||||
 | 
					            obstacle_detected = true;
 | 
				
			||||||
 | 
					            break;
 | 
				
			||||||
 | 
					        }
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    if (obstacle_detected) {
 | 
				
			||||||
 | 
					        // 处理避障逻辑
 | 
				
			||||||
 | 
					        ROS_WARN("stop!!!");
 | 
				
			||||||
 | 
					        stopRobot();
 | 
				
			||||||
 | 
					    } else {
 | 
				
			||||||
 | 
					        // 继续正常运动
 | 
				
			||||||
 | 
					        continueMoving();
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					void stopRobot() {
 | 
				
			||||||
 | 
					    geometry_msgs::Twist stop_cmd;
 | 
				
			||||||
 | 
					    stop_cmd.linear.x = 0;
 | 
				
			||||||
 | 
					    stop_cmd.angular.z = 0;
 | 
				
			||||||
 | 
					    cmd_pid_publisher_.publish(stop_cmd);
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					void continueMoving() {
 | 
				
			||||||
 | 
					    // 继续向目标移动的逻辑
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
    ros::NodeHandle nh_;
 | 
					    ros::NodeHandle nh_;
 | 
				
			||||||
    ros::Subscriber pose_subscriber_;
 | 
					    ros::Subscriber pose_subscriber_;
 | 
				
			||||||
    ros::Subscriber goal_subscriber_;
 | 
					    ros::Subscriber goal_subscriber_;
 | 
				
			||||||
@ -146,7 +181,9 @@ private:
 | 
				
			|||||||
    std::vector<TargetPose> target_poses_;
 | 
					    std::vector<TargetPose> target_poses_;
 | 
				
			||||||
    PIDController x_controller_, y_controller_, yaw_controller_;
 | 
					    PIDController x_controller_, y_controller_, yaw_controller_;
 | 
				
			||||||
    TargetPose target_;
 | 
					    TargetPose target_;
 | 
				
			||||||
 | 
					    ros::Subscriber laser_sub;
 | 
				
			||||||
    int robot_mode_;
 | 
					    int robot_mode_;
 | 
				
			||||||
 | 
					    float min_distance = 0.5; // 最小安全距离,单位:米
 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
int main(int argc, char **argv) {
 | 
					int main(int argc, char **argv) {
 | 
				
			||||||
@ -138,6 +138,24 @@ void write3float(float x,float y,float yaw)
 | 
				
			|||||||
    // 通过串口下发数据
 | 
					    // 通过串口下发数据
 | 
				
			||||||
    boost::asio::write(sp, boost::asio::buffer(buf));
 | 
					    boost::asio::write(sp, boost::asio::buffer(buf));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					void write3float2(float x,float y,float yaw)
 | 
				
			||||||
 | 
					{   X.d  = x;//mm/s
 | 
				
			||||||
 | 
					    Y.d = y;
 | 
				
			||||||
 | 
					    YAW.d = yaw;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					   unsigned char buf[15] = {0};//
 | 
				
			||||||
 | 
					    buf[0]=0x11;
 | 
				
			||||||
 | 
					    buf[1]=0x09;
 | 
				
			||||||
 | 
					    buf[2]=0x00;
 | 
				
			||||||
 | 
					    buf[15]=0xFE;
 | 
				
			||||||
 | 
					    for(int i=0;i<4;i++){
 | 
				
			||||||
 | 
					        buf[i+3]=X.data[i];
 | 
				
			||||||
 | 
					        buf[i+7]=Y.data[i];
 | 
				
			||||||
 | 
					        buf[i+11]=YAW.data[i];
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
 | 
					    boost::asio::write(sp, boost::asio::buffer(buf));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
std::string string2hex(const std::string& input)
 | 
					std::string string2hex(const std::string& input)
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
 | 
				
			|||||||
		Loading…
	
		Reference in New Issue
	
	Block a user