ultrasonic
parent
1861adb239
commit
e73ef2a5a8
|
@ -11,6 +11,7 @@ find_package(catkin REQUIRED COMPONENTS
|
||||||
|
|
||||||
find_package(OpenCV REQUIRED)
|
find_package(OpenCV REQUIRED)
|
||||||
find_package(Threads REQUIRED)
|
find_package(Threads REQUIRED)
|
||||||
|
find_package(Boost REQUIRED COMPONENTS thread chrono)
|
||||||
|
|
||||||
|
|
||||||
# generate_messages(
|
# generate_messages(
|
||||||
|
@ -41,10 +42,13 @@ add_library(
|
||||||
include/upbot_vision/preprocess.h
|
include/upbot_vision/preprocess.h
|
||||||
include/upbot_vision/ranging.h
|
include/upbot_vision/ranging.h
|
||||||
include/upbot_vision/Timer.h
|
include/upbot_vision/Timer.h
|
||||||
|
include/upbot_vision/ultrasonic.h
|
||||||
|
|
||||||
src/detection.cc
|
src/detection.cc
|
||||||
src/postprocess.cc
|
src/postprocess.cc
|
||||||
src/preprocess.cc
|
src/preprocess.cc
|
||||||
src/ranging.cc
|
src/ranging.cc
|
||||||
|
src/ultrasonic.cc
|
||||||
)
|
)
|
||||||
|
|
||||||
add_dependencies(head ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
add_dependencies(head ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||||
|
@ -53,13 +57,14 @@ target_link_libraries(head
|
||||||
|
|
||||||
)
|
)
|
||||||
add_executable(main src/main.cc)
|
add_executable(main src/main.cc)
|
||||||
# add_executable(sub_dis src/sub_dis.cc)
|
add_executable(ultrasonic src/ultrasonic.cc)
|
||||||
add_dependencies(main ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
add_dependencies(main ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||||
# add_dependencies(sub_dis ${${PROJECT_NAME}_EXPORTED_TARGETS} upbot_vision_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
|
# add_dependencies(sub_dis ${${PROJECT_NAME}_EXPORTED_TARGETS} upbot_vision_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
|
||||||
|
target_link_libraries(ultrasonic
|
||||||
|
${Boost_LIBRARIES} Boost::thread Boost::chrono
|
||||||
|
${catkin_LIBRARIES}
|
||||||
|
)
|
||||||
|
|
||||||
# target_link_libraries(sub_dis
|
|
||||||
# ${catkin_LIBRARIES}
|
|
||||||
# )
|
|
||||||
target_link_libraries(main
|
target_link_libraries(main
|
||||||
head
|
head
|
||||||
${catkin_LIBRARIES}
|
${catkin_LIBRARIES}
|
||||||
|
|
|
@ -0,0 +1,24 @@
|
||||||
|
#include <ros/ros.h>
|
||||||
|
#include <sensor_msgs/Range.h>
|
||||||
|
#include <boost/asio.hpp>
|
||||||
|
#include <boost/bind.hpp>
|
||||||
|
#include <boost/thread.hpp>
|
||||||
|
|
||||||
|
|
||||||
|
class UltrasonicNode {
|
||||||
|
private:
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
ros::Publisher ultrasonic_pub;
|
||||||
|
boost::asio::io_service io;
|
||||||
|
boost::asio::serial_port serial;
|
||||||
|
|
||||||
|
public:
|
||||||
|
UltrasonicNode() : nh("~"), serial(io), ultrasonic_pub(nh.advertise<sensor_msgs::Range>("ultrasonic", 1)) {
|
||||||
|
std::string port_name;
|
||||||
|
nh.param<std::string>("port", port_name, "/dev/ttyUSB0");
|
||||||
|
serial.open(port_name);
|
||||||
|
serial.set_option(boost::asio::serial_port_base::baud_rate(9600));
|
||||||
|
}
|
||||||
|
void readUltrasonic();
|
||||||
|
};
|
||||||
|
|
|
@ -0,0 +1,46 @@
|
||||||
|
#include "upbot_vision/ultrasonic.h"
|
||||||
|
|
||||||
|
|
||||||
|
void UltrasonicNode::readUltrasonic() {
|
||||||
|
try {
|
||||||
|
while (true) {
|
||||||
|
// 发送数据
|
||||||
|
serial.write_some(boost::asio::buffer("\xA0", 1));
|
||||||
|
// ROS_INFO("Data sent: 0xA0");
|
||||||
|
|
||||||
|
// 读取数据
|
||||||
|
char data[3];
|
||||||
|
boost::asio::read(serial, boost::asio::buffer(data, 3));
|
||||||
|
sensor_msgs::Range range_msg;
|
||||||
|
range_msg.header.stamp = ros::Time::now();
|
||||||
|
range_msg.header.frame_id = "ultrasonic_sensor";
|
||||||
|
range_msg.radiation_type = sensor_msgs::Range::ULTRASOUND;
|
||||||
|
range_msg.field_of_view = M_PI; // Assuming 180 degrees
|
||||||
|
range_msg.min_range = 0.0; // Minimum range in meters
|
||||||
|
range_msg.max_range = 5.0; // Maximum range in meters
|
||||||
|
range_msg.range = ((data[0] << 16) + (data[1] << 8 ) + data[2]) / 1000.0; // Convert to meters
|
||||||
|
ultrasonic_pub.publish(range_msg);
|
||||||
|
ROS_INFO("Received ultrasonic data: %f mm", range_msg.range);
|
||||||
|
|
||||||
|
// 延迟一段时间
|
||||||
|
boost::this_thread::sleep_for(boost::chrono::milliseconds(100));
|
||||||
|
}
|
||||||
|
} catch (std::exception& e) {
|
||||||
|
ROS_ERROR("Error reading ultrasonic data: %s", e.what());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int main(int argc, char** argv) {
|
||||||
|
ros::init(argc, argv, "ultrasonic_node");
|
||||||
|
UltrasonicNode ultrasonic_node;
|
||||||
|
ros::Rate rate(10); // 10 Hz
|
||||||
|
|
||||||
|
while (ros::ok()) {
|
||||||
|
ultrasonic_node.readUltrasonic();
|
||||||
|
ros::spinOnce();
|
||||||
|
rate.sleep();
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
Loading…
Reference in New Issue