add the spark_test
This commit is contained in:
parent
3fed156a87
commit
1c4870007c
27
onekey.sh
27
onekey.sh
|
@ -695,16 +695,25 @@ spark_dock(){
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
spark_test(){
|
spark_test_mode(){
|
||||||
|
|
||||||
echo -e "${Info}"
|
|
||||||
echo -e "${Info} SPARK test"
|
|
||||||
PROJECTPATH=$(cd `dirname $0`; pwd)
|
PROJECTPATH=$(cd `dirname $0`; pwd)
|
||||||
source ${PROJECTPATH}/devel/setup.bash
|
source ${PROJECTPATH}/devel/setup.bash
|
||||||
|
echo -e "${Info}老化测试程序,请将机器人放在一个50X50CM的方格中间进行测试,请选择:
|
||||||
echo && stty erase ^? && read -p "按回车键(Enter)开始:"
|
1.执行5分钟的检测功能;
|
||||||
print_command "roslaunch spark_test turn_test.launch"
|
2.执行老化检测功能,直至断电。"
|
||||||
roslaunch spark_test turn_test.launch
|
echo -e "${Info}退出请输入:Ctrl + c "
|
||||||
|
echo && stty erase ^? && read -p "请选择 1 或 2 :" chnum
|
||||||
|
case "$chnum" in
|
||||||
|
1)
|
||||||
|
roslaunch spark_test all_run_test_st.launch camera_type_tel:=${CAMERATYPE}
|
||||||
|
;;
|
||||||
|
2)
|
||||||
|
roslaunch spark_test all_run_test.launch camera_type_tel:=${CAMERATYPE}
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
echo -e "${Error} 退出!"
|
||||||
|
;;
|
||||||
|
esac
|
||||||
}
|
}
|
||||||
|
|
||||||
#让SPARK使用深度摄像头绘制地图
|
#让SPARK使用深度摄像头绘制地图
|
||||||
|
@ -1003,7 +1012,7 @@ case "$num" in
|
||||||
spark_dock
|
spark_dock
|
||||||
;;
|
;;
|
||||||
98)
|
98)
|
||||||
spark_test
|
spark_test_mode
|
||||||
;;
|
;;
|
||||||
*)
|
*)
|
||||||
echo -e "${Error} 请输入正确的数字 "
|
echo -e "${Error} 请输入正确的数字 "
|
||||||
|
|
|
@ -9,8 +9,8 @@ find_package(catkin REQUIRED COMPONENTS
|
||||||
rospy
|
rospy
|
||||||
std_msgs
|
std_msgs
|
||||||
pcl_ros
|
pcl_ros
|
||||||
tf
|
|
||||||
spark_base
|
spark_base
|
||||||
|
spark_carry_object
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
||||||
|
@ -18,12 +18,10 @@ find_package(catkin REQUIRED COMPONENTS
|
||||||
## catkin specific configuration ##
|
## catkin specific configuration ##
|
||||||
###################################=
|
###################################=
|
||||||
catkin_package(
|
catkin_package(
|
||||||
LIBRARIES
|
# INCLUDE_DIRS include
|
||||||
CATKIN_DEPENDS roscpp rospy std_msgs tf
|
# LIBRARIES spark_test
|
||||||
DEPENDS system_lib
|
# CATKIN_DEPENDS roscpp rospy std_msgs spark_base
|
||||||
)
|
# DEPENDS system_lib
|
||||||
include_directories(include
|
|
||||||
${catkin_INCLUDE_DIRS}
|
|
||||||
)
|
)
|
||||||
|
|
||||||
###########
|
###########
|
||||||
|
@ -52,6 +50,13 @@ add_dependencies(spark_test_topic_node
|
||||||
target_link_libraries(spark_test_topic_node ${catkin_LIBRARIES})
|
target_link_libraries(spark_test_topic_node ${catkin_LIBRARIES})
|
||||||
|
|
||||||
|
|
||||||
|
add_executable(spark_turn_left_right_node src/spark_turn_left_right.cpp)
|
||||||
|
add_dependencies(spark_turn_left_right_node
|
||||||
|
${${PROJECT_NAME}_EXPORTED_TARGETS}
|
||||||
|
${catkin_EXPORTED_TARGETS}
|
||||||
|
${PROJECT_NAME}_generate_messages_cpp)
|
||||||
|
target_link_libraries(spark_turn_left_right_node ${catkin_LIBRARIES})
|
||||||
|
|
||||||
add_executable(spark_test_motion_node src/spark_test_motion.cpp)
|
add_executable(spark_test_motion_node src/spark_test_motion.cpp)
|
||||||
add_dependencies(spark_test_motion_node
|
add_dependencies(spark_test_motion_node
|
||||||
${${PROJECT_NAME}_EXPORTED_TARGETS}
|
${${PROJECT_NAME}_EXPORTED_TARGETS}
|
||||||
|
@ -60,6 +65,12 @@ add_dependencies(spark_test_motion_node
|
||||||
target_link_libraries(spark_test_motion_node ${catkin_LIBRARIES})
|
target_link_libraries(spark_test_motion_node ${catkin_LIBRARIES})
|
||||||
|
|
||||||
|
|
||||||
|
add_executable(spark_turn_left_right_st_node src/spark_turn_left_right_st.cpp)
|
||||||
|
add_dependencies(spark_turn_left_right_st_node
|
||||||
|
${${PROJECT_NAME}_EXPORTED_TARGETS}
|
||||||
|
${catkin_EXPORTED_TARGETS}
|
||||||
|
${PROJECT_NAME}_generate_messages_cpp)
|
||||||
|
target_link_libraries(spark_turn_left_right_st_node ${catkin_LIBRARIES})
|
||||||
|
|
||||||
#############
|
#############
|
||||||
## Install ##
|
## Install ##
|
||||||
|
|
|
@ -0,0 +1,28 @@
|
||||||
|
<!-- object detect -->
|
||||||
|
|
||||||
|
<launch>
|
||||||
|
<!-- camera -->
|
||||||
|
<arg name="camera_type_tel" default="" doc="camera type [astrapro, astra]"/>
|
||||||
|
|
||||||
|
<node pkg= "tensorflow_object_detector" name="detect_ros" type="detect_ros.py" output="screen">
|
||||||
|
<remap from="image" to="/camera/color/image_raw" if="$(eval arg('camera_type_tel')=='d435')"/>
|
||||||
|
<remap from="image" to="/camera/rgb/image_raw" unless="$(eval arg('camera_type_tel')=='d435')"/>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<!-- rviz -->
|
||||||
|
<arg name ="rviz" default="true" />
|
||||||
|
<arg name ="rviz_file" default="$(find tensorflow_object_detector)/config/display.rviz"/>
|
||||||
|
<node pkg ="rviz" type="rviz" name="rviz" output="screen" args= "-d $(arg rviz_file)" if="$(arg rviz)"/>
|
||||||
|
|
||||||
|
<!-- spark底盘驱动,机器人描述,底盘,相机 -->
|
||||||
|
<include file="$(find spark_bringup)/launch/driver_bringup.launch">
|
||||||
|
<arg name="camera_types" value="$(arg camera_type_tel)"/>
|
||||||
|
<arg name="start_base" value="true"/>
|
||||||
|
</include>
|
||||||
|
<!--UARM机械臂 -->
|
||||||
|
<include file="$(find swiftpro)/launch/pro_control_nomoveit.launch"/>
|
||||||
|
|
||||||
|
<node pkg="spark_test" type="spark_turn_left_right_node" name="spark_turn_left_right_node" output="screen"/>
|
||||||
|
|
||||||
|
|
||||||
|
</launch>
|
|
@ -0,0 +1,28 @@
|
||||||
|
<!-- object detect -->
|
||||||
|
|
||||||
|
<launch>
|
||||||
|
<!-- camera -->
|
||||||
|
<arg name="camera_type_tel" default="" doc="camera type [astrapro, astra]"/>
|
||||||
|
|
||||||
|
<node pkg= "tensorflow_object_detector" name="detect_ros" type="detect_ros.py" output="screen">
|
||||||
|
<remap from="image" to="/camera/color/image_raw" if="$(eval arg('camera_type_tel')=='d435')"/>
|
||||||
|
<remap from="image" to="/camera/rgb/image_raw" unless="$(eval arg('camera_type_tel')=='d435')"/>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<!-- rviz -->
|
||||||
|
<arg name ="rviz" default="true" />
|
||||||
|
<arg name ="rviz_file" default="$(find tensorflow_object_detector)/config/display.rviz"/>
|
||||||
|
<node pkg ="rviz" type="rviz" name="rviz" output="screen" args= "-d $(arg rviz_file)" if="$(arg rviz)"/>
|
||||||
|
|
||||||
|
<!-- spark底盘驱动,机器人描述,底盘,相机 -->
|
||||||
|
<include file="$(find spark_bringup)/launch/driver_bringup.launch">
|
||||||
|
<arg name="camera_types" value="$(arg camera_type_tel)"/>
|
||||||
|
<arg name="start_base" value="true"/>
|
||||||
|
</include>
|
||||||
|
<!--UARM机械臂 -->
|
||||||
|
<include file="$(find swiftpro)/launch/pro_control_nomoveit.launch"/>
|
||||||
|
|
||||||
|
<node pkg="spark_test" type="spark_turn_left_right_st_node" name="spark_turn_left_right_st_node" output="screen"/>
|
||||||
|
|
||||||
|
|
||||||
|
</launch>
|
|
@ -48,8 +48,6 @@
|
||||||
<run_depend>rospy</run_depend>
|
<run_depend>rospy</run_depend>
|
||||||
<run_depend>std_msgs</run_depend>
|
<run_depend>std_msgs</run_depend>
|
||||||
<run_depend>spark_base</run_depend>
|
<run_depend>spark_base</run_depend>
|
||||||
<build_depend>tf</build_depend>
|
|
||||||
<run_depend>tf</run_depend>
|
|
||||||
|
|
||||||
<!-- The export tag contains other, unspecified, tags -->
|
<!-- The export tag contains other, unspecified, tags -->
|
||||||
<export>
|
<export>
|
||||||
|
|
|
@ -1,11 +1,11 @@
|
||||||
#include "ros/ros.h"
|
#include "ros/ros.h"
|
||||||
|
#include <boost/function.hpp>
|
||||||
|
#include <boost/thread/thread.hpp>
|
||||||
#include <pcl_ros/point_cloud.h>
|
#include <pcl_ros/point_cloud.h>
|
||||||
#include <pcl/point_types.h>
|
#include <pcl/point_types.h>
|
||||||
#include <sensor_msgs/Image.h>
|
#include <sensor_msgs/Image.h>
|
||||||
#include <geometry_msgs/Twist.h>
|
#include <geometry_msgs/Twist.h>
|
||||||
#include <boost/function.hpp>
|
|
||||||
#include <boost/thread/thread.hpp>
|
|
||||||
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
|
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
|
||||||
|
|
||||||
class MotionTest
|
class MotionTest
|
||||||
|
@ -33,11 +33,9 @@ public:
|
||||||
bool testMotion()
|
bool testMotion()
|
||||||
{
|
{
|
||||||
ros::Rate rate(10);
|
ros::Rate rate(10);
|
||||||
while(ros::ok)
|
|
||||||
{
|
|
||||||
double prev_sec = ros::Time().now().toSec();
|
double prev_sec = ros::Time().now().toSec();
|
||||||
int sec = 10;
|
int sec = 10;
|
||||||
while (ros::ok)
|
while (1)
|
||||||
{
|
{
|
||||||
//逆时针旋转
|
//逆时针旋转
|
||||||
if (ros::Time().now().toSec() - prev_sec > sec)
|
if (ros::Time().now().toSec() - prev_sec > sec)
|
||||||
|
@ -47,7 +45,7 @@ public:
|
||||||
rate.sleep();
|
rate.sleep();
|
||||||
}
|
}
|
||||||
prev_sec = ros::Time().now().toSec();
|
prev_sec = ros::Time().now().toSec();
|
||||||
while (ros::ok)
|
while (1)
|
||||||
{
|
{
|
||||||
//顺时针旋转
|
//顺时针旋转
|
||||||
if (ros::Time().now().toSec() - prev_sec > sec)
|
if (ros::Time().now().toSec() - prev_sec > sec)
|
||||||
|
@ -57,7 +55,7 @@ public:
|
||||||
rate.sleep();
|
rate.sleep();
|
||||||
}
|
}
|
||||||
prev_sec = ros::Time().now().toSec();
|
prev_sec = ros::Time().now().toSec();
|
||||||
/* while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
//逆时针同心圆旋转
|
//逆时针同心圆旋转
|
||||||
if (ros::Time().now().toSec() - prev_sec > sec)
|
if (ros::Time().now().toSec() - prev_sec > sec)
|
||||||
|
@ -76,7 +74,6 @@ public:
|
||||||
ROS_INFO("shunshizhen tongxinyuan");
|
ROS_INFO("shunshizhen tongxinyuan");
|
||||||
testTurnBody(0.2, -1, 10);
|
testTurnBody(0.2, -1, 10);
|
||||||
rate.sleep();
|
rate.sleep();
|
||||||
}*/
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,106 @@
|
||||||
|
#include "ros/ros.h"
|
||||||
|
#include <boost/function.hpp>
|
||||||
|
#include <boost/thread/thread.hpp>
|
||||||
|
#include <pcl_ros/point_cloud.h>
|
||||||
|
#include <pcl/point_types.h>
|
||||||
|
#include <sensor_msgs/Image.h>
|
||||||
|
#include <geometry_msgs/Twist.h>
|
||||||
|
#include "spark_carry_object/status.h"
|
||||||
|
#include "spark_carry_object/position.h"
|
||||||
|
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
|
||||||
|
|
||||||
|
class MotionTest
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
ros::NodeHandle nhandle;
|
||||||
|
boost::thread* test_motion_thread_;
|
||||||
|
ros::Publisher cmd_pub;
|
||||||
|
ros::Publisher pump_pub;
|
||||||
|
ros::Publisher pos_pub;
|
||||||
|
MotionTest(ros::NodeHandle in_nh)
|
||||||
|
{
|
||||||
|
nhandle = in_nh;
|
||||||
|
|
||||||
|
cmd_pub = nhandle.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
|
||||||
|
pump_pub = nhandle.advertise<spark_carry_object::status>("pump_topic", 1);
|
||||||
|
pos_pub = nhandle.advertise<spark_carry_object::position>("position_write_topic", 1);
|
||||||
|
test_motion_thread_ = new boost::thread(boost::bind(&MotionTest::testMotion, this));
|
||||||
|
}
|
||||||
|
|
||||||
|
~MotionTest()
|
||||||
|
{
|
||||||
|
spark_carry_object::status onoff;
|
||||||
|
onoff.status = 0;
|
||||||
|
pump_pub.publish(onoff);
|
||||||
|
if (test_motion_thread_ != NULL)
|
||||||
|
{
|
||||||
|
delete test_motion_thread_;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool testMotion()
|
||||||
|
{
|
||||||
|
spark_carry_object::status onoff;
|
||||||
|
spark_carry_object::position pos;
|
||||||
|
ros::Rate rate(10);
|
||||||
|
onoff.status = 1;
|
||||||
|
pump_pub.publish(onoff);
|
||||||
|
pos.x = 120;
|
||||||
|
pos.y = 0;
|
||||||
|
pos.z = 35;
|
||||||
|
sleep(5);
|
||||||
|
pos_pub.publish(pos);
|
||||||
|
while(ros::ok)
|
||||||
|
{
|
||||||
|
pump_pub.publish(onoff);
|
||||||
|
double prev_sec = ros::Time().now().toSec();
|
||||||
|
int sec = 10;
|
||||||
|
ROS_INFO("ni shi zhen");
|
||||||
|
while (ros::ok)
|
||||||
|
{
|
||||||
|
//逆时针旋转
|
||||||
|
if (ros::Time().now().toSec() - prev_sec > sec)
|
||||||
|
break;
|
||||||
|
|
||||||
|
testTurnBody(0, 2, 10);
|
||||||
|
rate.sleep();
|
||||||
|
}
|
||||||
|
ROS_INFO("shen shi zhen");
|
||||||
|
prev_sec = ros::Time().now().toSec();
|
||||||
|
while (ros::ok)
|
||||||
|
{
|
||||||
|
//顺时针旋转
|
||||||
|
if (ros::Time().now().toSec() - prev_sec > sec)
|
||||||
|
break;
|
||||||
|
|
||||||
|
testTurnBody(0, -2, 10);
|
||||||
|
rate.sleep();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
onoff.status = 0;
|
||||||
|
pump_pub.publish(onoff);
|
||||||
|
}
|
||||||
|
|
||||||
|
void testTurnBody(float linearx, float angularz, float sec)
|
||||||
|
{
|
||||||
|
geometry_msgs::Twist vel;
|
||||||
|
vel.linear.x = linearx;
|
||||||
|
vel.angular.z = angularz;
|
||||||
|
cmd_pub.publish(vel);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char** argv)
|
||||||
|
{
|
||||||
|
ros::init(argc, argv, "spark_test_node");
|
||||||
|
ROS_INFO("Spark test bring up");
|
||||||
|
|
||||||
|
ros::NodeHandle n;
|
||||||
|
MotionTest test(n);
|
||||||
|
|
||||||
|
// start to test the spark
|
||||||
|
// test.testTopicStatus();
|
||||||
|
ROS_INFO("Spark test stop");
|
||||||
|
ros::spin();
|
||||||
|
return 0;
|
||||||
|
}
|
|
@ -0,0 +1,116 @@
|
||||||
|
#include "ros/ros.h"
|
||||||
|
#include <boost/function.hpp>
|
||||||
|
#include <boost/thread/thread.hpp>
|
||||||
|
#include <pcl_ros/point_cloud.h>
|
||||||
|
#include <pcl/point_types.h>
|
||||||
|
#include <sensor_msgs/Image.h>
|
||||||
|
#include <geometry_msgs/Twist.h>
|
||||||
|
#include "spark_carry_object/status.h"
|
||||||
|
#include "spark_carry_object/position.h"
|
||||||
|
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
|
||||||
|
|
||||||
|
class MotionTest
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
ros::NodeHandle nhandle;
|
||||||
|
boost::thread* test_motion_thread_;
|
||||||
|
ros::Publisher cmd_pub;
|
||||||
|
ros::Publisher pump_pub;
|
||||||
|
ros::Publisher pos_pub;
|
||||||
|
MotionTest(ros::NodeHandle in_nh)
|
||||||
|
{
|
||||||
|
nhandle = in_nh;
|
||||||
|
|
||||||
|
cmd_pub = nhandle.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
|
||||||
|
pump_pub = nhandle.advertise<spark_carry_object::status>("pump_topic", 1);
|
||||||
|
pos_pub = nhandle.advertise<spark_carry_object::position>("position_write_topic", 1);
|
||||||
|
test_motion_thread_ = new boost::thread(boost::bind(&MotionTest::testMotion, this));
|
||||||
|
}
|
||||||
|
|
||||||
|
~MotionTest()
|
||||||
|
{
|
||||||
|
spark_carry_object::status onoff;
|
||||||
|
onoff.status = 0;
|
||||||
|
pump_pub.publish(onoff);
|
||||||
|
if (test_motion_thread_ != NULL)
|
||||||
|
{
|
||||||
|
delete test_motion_thread_;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool testMotion()
|
||||||
|
{
|
||||||
|
spark_carry_object::status onoff;
|
||||||
|
spark_carry_object::position pos;
|
||||||
|
ros::Rate rate(10);
|
||||||
|
onoff.status = 1;
|
||||||
|
pump_pub.publish(onoff);
|
||||||
|
pos.x = 120;
|
||||||
|
pos.y = 0;
|
||||||
|
pos.z = 35;
|
||||||
|
sleep(5);
|
||||||
|
pos_pub.publish(pos);
|
||||||
|
double start_sec = ros::Time().now().toSec();
|
||||||
|
int keep_sec = 300;
|
||||||
|
ROS_INFO("time is start! start turning.");
|
||||||
|
while(ros::ok)
|
||||||
|
{
|
||||||
|
pump_pub.publish(onoff);
|
||||||
|
double prev_sec = ros::Time().now().toSec();
|
||||||
|
int sec = 10;
|
||||||
|
ROS_INFO("ni shi zhen");
|
||||||
|
while (ros::ok)
|
||||||
|
{
|
||||||
|
//逆时针旋转
|
||||||
|
if (ros::Time().now().toSec() - prev_sec > sec)
|
||||||
|
break;
|
||||||
|
|
||||||
|
testTurnBody(0, 2, 10);
|
||||||
|
rate.sleep();
|
||||||
|
}
|
||||||
|
ROS_INFO("shen shi zhen");
|
||||||
|
prev_sec = ros::Time().now().toSec();
|
||||||
|
while (ros::ok)
|
||||||
|
{
|
||||||
|
|
||||||
|
//顺时针旋转
|
||||||
|
if (ros::Time().now().toSec() - prev_sec > sec)
|
||||||
|
break;
|
||||||
|
|
||||||
|
testTurnBody(0, -2, 10);
|
||||||
|
rate.sleep();
|
||||||
|
}
|
||||||
|
if (ros::Time().now().toSec() - start_sec > keep_sec)
|
||||||
|
{
|
||||||
|
onoff.status = 0;
|
||||||
|
pump_pub.publish(onoff);
|
||||||
|
ROS_WARN("time is over! stop turning.");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void testTurnBody(float linearx, float angularz, float sec)
|
||||||
|
{
|
||||||
|
geometry_msgs::Twist vel;
|
||||||
|
vel.linear.x = linearx;
|
||||||
|
vel.angular.z = angularz;
|
||||||
|
cmd_pub.publish(vel);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char** argv)
|
||||||
|
{
|
||||||
|
ros::init(argc, argv, "spark_test_node");
|
||||||
|
ROS_INFO("Spark test bring up");
|
||||||
|
|
||||||
|
ros::NodeHandle n;
|
||||||
|
MotionTest test(n);
|
||||||
|
|
||||||
|
// start to test the spark
|
||||||
|
// test.testTopicStatus();
|
||||||
|
//ROS_INFO("Spark test stop");
|
||||||
|
ros::spin();
|
||||||
|
return 0;
|
||||||
|
}
|
|
@ -8,9 +8,9 @@ from threading import Thread, Event
|
||||||
from lib import Microphone,AipSpeech
|
from lib import Microphone,AipSpeech
|
||||||
|
|
||||||
""" 你的 APPID AK SK """
|
""" 你的 APPID AK SK """
|
||||||
APP_ID = '10475584'
|
APP_ID = '23797700'
|
||||||
API_KEY = 'm2zeD2S8ft8z6Y0oUblsIZhy'
|
API_KEY = 'dK8rz5DG9pPi90cgQVtx1ddn'
|
||||||
SECRET_KEY = 'Y226Y4YCRzpYXy3E3MTG0xxyqRGZYG50'
|
SECRET_KEY = 'X1lzayj5RQwfkoLHXHd5DALRvFZpjhBP'
|
||||||
|
|
||||||
def main():
|
def main():
|
||||||
#logging.basicConfig(level=logging.DEBUG)
|
#logging.basicConfig(level=logging.DEBUG)
|
||||||
|
|
Loading…
Reference in New Issue