加入机械臂相关选择。修改摄像头设备参数

This commit is contained in:
litian.zhuang 2022-04-01 12:05:29 +08:00
parent 0a76774e0a
commit 8ab66c08d0
23 changed files with 690 additions and 57 deletions

View File

@ -45,15 +45,24 @@ check_dev(){
echo -e "${Error} 底盘没有正确连接,请确认正确连接!!" echo -e "${Error} 底盘没有正确连接,请确认正确连接!!"
fi fi
#检查机械臂 #检查机械臂
if [ ! -n "$(lsusb -d 2341:0042)" ]; then if [ -n "$(lsusb -d 2341:0042)" ]; then
echo -e "${Error} 机械臂没有正确连接,请确认正确连接!!" echo -e "${Info} 正在使用UARM机械臂"
ARMTYPE="uarm"
elif [ -n "$(lsusb -d 2e88:4603)" ]; then
echo -e "${Info} 正在使用射手座机械臂"
ARMTYPE="sagittarius_arm"
else
echo -e "${Error} 机械臂没有正确连接或未上电,请确认正确连接!!"
ARMTYPE="uarm"
fi fi
#检查摄像头 #检查摄像头
check_camera check_camera
#检查雷达 #检查雷达
check_lidar check_lidar
} }
#检查雷达设备 #检查雷达设备
check_lidar(){ check_lidar(){
BASEPATH=$(cd `dirname $0`; pwd) BASEPATH=$(cd `dirname $0`; pwd)
@ -301,6 +310,7 @@ master_uri_setup(){
wlan_ip=`/sbin/ifconfig wlan0|grep 'inet '|awk '{print $2}'` wlan_ip=`/sbin/ifconfig wlan0|grep 'inet '|awk '{print $2}'`
enp3s_ip=`/sbin/ifconfig enp3s0|grep 'inet '|awk '{print $2}'` enp3s_ip=`/sbin/ifconfig enp3s0|grep 'inet '|awk '{print $2}'`
wlo1_ip=`/sbin/ifconfig wlo1|grep 'inet '|awk '{print $2}'` wlo1_ip=`/sbin/ifconfig wlo1|grep 'inet '|awk '{print $2}'`
wlp0s_ip=`/sbin/ifconfig wlp0s20f3|grep 'inet '|awk '{print $2}'`
if [ $eth_ip ]; then if [ $eth_ip ]; then
echo -e "${Info}使用有线网络eth0" echo -e "${Info}使用有线网络eth0"
local_ip=$eth_ip local_ip=$eth_ip
@ -316,9 +326,12 @@ master_uri_setup(){
elif [ $wlan_ip ]; then elif [ $wlan_ip ]; then
echo -e "${Info}使用无线网络wlan0" echo -e "${Info}使用无线网络wlan0"
local_ip=$wlan_ip local_ip=$wlan_ip
elif [ $enp3s_ip ]; then elif [ $enp3s_ip ]; then
echo -e "${Info}使用无线网络enp3s0" echo -e "${Info}使用无线网络enp3s0"
local_ip=$enp3s_ip local_ip=$enp3s_ip
elif [ $wlp0s_ip ]; then
echo -e "${Info}使用无线网络wlp0s20f3"
local_ip=$wlp0s_ip
fi fi
export ROS_HOSTNAME=$local_ip export ROS_HOSTNAME=$local_ip
export ROS_MASTER_URI="http://${local_ip}:11311" export ROS_MASTER_URI="http://${local_ip}:11311"
@ -347,8 +360,8 @@ let_robot_go(){
echo -e "${Info} " echo -e "${Info} "
echo -e "${Info} 退出请输入Ctrl + c " echo -e "${Info} 退出请输入Ctrl + c "
echo && stty erase ^? && read -p "按回车键Enter开始" echo && stty erase ^? && read -p "按回车键Enter开始"
print_command "roslaunch spark_teleop teleop.launch camera_type_tel:=${CAMERATYPE} lidar_type_tel:=${LIDARTYPE}" print_command "roslaunch spark_teleop teleop.launch camera_type_tel:=${CAMERATYPE} lidar_type_tel:=${LIDARTYPE} enable_arm_tel:=false"
roslaunch spark_teleop teleop.launch camera_type_tel:=${CAMERATYPE} lidar_type_tel:=${LIDARTYPE} roslaunch spark_teleop teleop.launch camera_type_tel:=${CAMERATYPE} lidar_type_tel:=${LIDARTYPE} enable_arm_tel:="false"
} }

View File

@ -6,7 +6,7 @@
<!-- spark底盘驱动机器人描述,底盘,相机 --> <!-- spark底盘驱动机器人描述,底盘,相机 -->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="start_base" value="true"/> <arg name="start_base" value="true"/>
</include> </include>

View File

@ -16,7 +16,7 @@
<!-- spark底盘驱动机器人描述,底盘,相机 --> <!-- spark底盘驱动机器人描述,底盘,相机 -->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="start_base" value="false"/> <arg name="start_base" value="false"/>
</include> </include>

View File

@ -5,11 +5,11 @@
<arg name="start_camera" default="true"/> <arg name="start_camera" default="true"/>
<arg name="serialport" default="/dev/sparkBase"/> <arg name="serialport" default="/dev/sparkBase"/>
<arg name="dp_rgist" default="false"/> <arg name="dp_rgist" default="false"/>
<arg name="camera_types" default="astrapro" doc="camera type [astrapro, astra,d435]"/> <arg name="camera_type_tel" default="astrapro" doc="camera type [astrapro, astra,d435]"/>
<arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/> <arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/>
<!--启动描述 --> <!--启动描述 -->
<include file="$(find spark_description)/launch/spark_description.launch"> <include file="$(find spark_description)/launch/spark_description.launch">
<arg name="camera_types" value="$(arg camera_types)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
</include> </include>

View File

@ -2,22 +2,33 @@
<launch> <launch>
<arg name="camera_types" default="astrapro" doc="camera types [asatra, astrapro, d435...]"/> <arg name="camera_type_tel" default="astrapro" doc="camera types [asatra, astrapro, d435...]"/>
<arg name="arm_type_tel" default="uarm" doc="arm types [uarm, sagittarius_arm]"/>
<arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/> <arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/>
<arg name="model" default="$(find spark_description)/robots/spark.urdf.xacro"/> <arg name="model" default="$(find spark_description)/robots/spark.urdf.xacro"/>
<arg name="enable_arm_tel" default="false"/>
<arg name="use_gui" default="false"/> <arg name="use_gui" default="false"/>
<arg name="publish_default_positions" default="true"/> <arg name="publish_default_positions" default="true"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(arg model)' camera_types:=$(arg camera_types) lidar_type_tel:=$(arg lidar_type_tel)"/> <param name="robot_description" command="$(find xacro)/xacro --inorder '$(arg model)' camera_type_tel:=$(arg camera_type_tel) lidar_type_tel:=$(arg lidar_type_tel)"/>
<group if="$(eval arg('arm_type_tel')=='sagittarius_arm')">
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="$(arg use_gui)"/>
<param name="publish_default_positions" value="$(arg publish_default_positions)" />
<rosparam param="source_list">[wheel_states,sagittarius_joint_states]</rosparam>
</node>
</group>
<group if="$(eval arg('arm_type_tel')=='uarm')">
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="$(arg use_gui)"/>
<param name="publish_default_positions" value="$(arg publish_default_positions)" />
<rosparam param="source_list">[wheel_states]</rosparam>
</node>
</group>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="$(arg use_gui)"/>
<param name="publish_default_positions" value="$(arg publish_default_positions)" />
<rosparam param="source_list">["wheel_states"]</rosparam>
</node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" /> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<!--show robo with rviz <!--show robo with rviz

View File

@ -1,13 +1,13 @@
<!--spark description with rviz--> <!--spark description with rviz-->
<launch> <launch>
<arg name="camera_types" default="astrapro" doc="camera types [asatra, astrapro, d435...]"/> <arg name="camera_type_tel" default="astrapro" doc="camera types [asatra, astrapro, d435...]"/>
<arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/> <arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/>
<arg name="model" default="$(find spark_description)/robots/spark.urdf.xacro"/> <arg name="model" default="$(find spark_description)/robots/spark.urdf.xacro"/>
<arg name="use_gui" default="false"/> <arg name="use_gui" default="false"/>
<arg name="publish_default_positions" default="true"/> <arg name="publish_default_positions" default="true"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(arg model)' camera_types:=$(arg camera_types) lidar_type_tel:=$(arg lidar_type_tel)"/> <param name="robot_description" command="$(find xacro)/xacro --inorder '$(arg model)' camera_type_tel:=$(arg camera_type_tel) lidar_type_tel:=$(arg lidar_type_tel)"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"> <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="$(arg use_gui)"/> <param name="use_gui" value="$(arg use_gui)"/>

View File

@ -7,10 +7,10 @@
--> -->
<robot name="spark" xmlns:xacro="http://ros.org/wiki/xacro"> <robot name="spark" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="camera_types" default="astrapro"/> <xacro:arg name="camera_type_tel" default="astrapro"/>
<xacro:arg name="lidar_type_tel" default="3iroboticslidar2"/> <xacro:arg name="lidar_type_tel" default="3iroboticslidar2"/>
<xacro:include filename="$(find spark_description)/urdf/spark_340.urdf.xacro"> <xacro:include filename="$(find spark_description)/urdf/spark_340.urdf.xacro">
<xacro:arg name="camera_types" value="$(arg camera_types)"/> <xacro:arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<xacro:arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <xacro:arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
</xacro:include> </xacro:include>
</robot> </robot>

View File

@ -8,9 +8,15 @@
<robot name="spark" xmlns:xacro="http://ros.org/wiki/xacro"> <robot name="spark" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="camera_types" default="astrapro"/> <xacro:arg name="enable_arm_tel" default="false"/>
<xacro:property name="enable_arm" value="$(arg enable_arm_tel)"/>
<xacro:arg name="arm_type_tel" default="uarm"/>
<xacro:property name="robot_arm_type" value="$(arg arm_type_tel)"/>
<xacro:property name="camera" value="$(arg camera_types)"/> <xacro:arg name="camera_type_tel" default="astrapro"/>
<xacro:property name="camera" value="$(arg camera_type_tel)"/>
<xacro:arg name="lidar_type_tel" default="astrapro"/> <xacro:arg name="lidar_type_tel" default="astrapro"/>
@ -33,11 +39,20 @@
</xacro:if> </xacro:if>
<xacro:if value="${camera == 'astrapro' or camera == 'astra'}"> <xacro:if value="${camera == 'astrapro' or camera == 'astra'}">
<xacro:include filename="$(find spark_description)/urdf/sensors/spark_$(arg camera_types).urdf"/> <xacro:include filename="$(find spark_description)/urdf/sensors/spark_$(arg camera_type_tel).urdf"/>
</xacro:if> </xacro:if>
<xacro:if value="${camera == 'd435'}"> <xacro:if value="${camera == 'd435'}">
<xacro:include filename="$(find spark_description)/urdf/sensors/spark_d435.urdf.xacro"/> <xacro:include filename="$(find spark_description)/urdf/sensors/spark_d435.urdf.xacro"/>
</xacro:if> </xacro:if>
<xacro:if value="${enable_arm == 'true'}">
<xacro:if value="${robot_arm_type == 'sagittarius_arm'}">
<xacro:include filename="$(find sagittarius_descriptions)/urdf/spark_sagittarius_descriptions.urdf"/>
</xacro:if>
<xacro:if value="${robot_arm_type == 'uarm'}">
<xacro:include filename="$(find swiftpro)/urdf/spark_pro_model.xacro"/>
</xacro:if>
</xacro:if>
</robot> </robot>

View File

@ -0,0 +1,599 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
Commit Version: 1.6.0-1-g15f4949 Build Version: 1.6.7594.29634
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="sagittarius_arm">
<!-- <joint name="sagittarius_base_joint" type="fixed">
<parent link="base_link"/>
<child link="sagittarius_base_frame" />
</joint>
<link name="sagittarius_base_frame"/>
-->
<joint name="sagittarius_base_link_joint" type="fixed">
<origin xyz="0.044 0 0.138" rpy="0 0 0"/>
<parent link="base_footprint"/>
<child link="sagittarius_base_link" />
</joint>
<link
name="sagittarius_base_link">
<inertial>
<origin
xyz="0.00793179544277737 2.48115460577673E-19 0.0312047945759253"
rpy="0 0 0" />
<mass
value="0.940146705073746" />
<inertia
ixx="0.000950195835062344"
ixy="3.14825974312405E-20"
ixz="-0.000200082473207336"
iyy="0.00267650790326047"
iyz="-1.01412991222915E-19"
izz="0.002902663900239" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/sagittarius_base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.1 0.1 0.1 0.9" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/sagittarius_base_link.STL" />
</geometry>
</collision>
</link>
<link
name="link1">
<inertial>
<origin
xyz="-7.74579608786574E-10 3.23354786979222E-12 0.0344870497564283"
rpy="0 0 0" />
<mass
value="0.123745079127031" />
<inertia
ixx="8.15779591743416E-05"
ixy="-4.25325094802094E-15"
ixz="-2.22201794150093E-12"
iyy="6.7607001964135E-05"
iyz="-1.59127137655435E-14"
izz="4.41297902395382E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link1.STL" />
</geometry>
<material
name="">
<color
rgba="0.1 0.1 0.1 0.9" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link1.STL" />
</geometry>
</collision>
</link>
<joint
name="joint1"
type="revolute">
<origin
xyz="0.045 0 0.07"
rpy="0 0 0" />
<parent
link="sagittarius_base_link" />
<child
link="link1" />
<axis
xyz="0 0 -1" />
<limit
lower="-2"
upper="2"
effort="0"
velocity="0" />
</joint>
<link
name="link2">
<inertial>
<origin
xyz="0.0119015312584793 -1.03639845764692E-08 0.150755903867182"
rpy="0 0 0" />
<mass
value="0.156160822791157" />
<inertia
ixx="0.000429266751802994"
ixy="-2.27426165787001E-11"
ixz="-5.58862834004722E-05"
iyy="0.000444676097748043"
iyz="-2.41993274420629E-10"
izz="7.916162292894E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link2.STL" />
</geometry>
<material
name="">
<color
rgba="0.1 0.1 0.1 0.9" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link2.STL" />
</geometry>
</collision>
</link>
<joint
name="joint2"
type="revolute">
<origin
xyz="0 -0.0001 0.055"
rpy="0 0 0" />
<parent
link="link1" />
<child
link="link2" />
<axis
xyz="0 -1 0" />
<limit
lower="-1.57"
upper="1.4"
effort="0"
velocity="0" />
</joint>
<link
name="link3">
<inertial>
<origin
xyz="0.054357321065004 -2.67256405253992E-08 0.00064594073830132"
rpy="0 0 0" />
<mass
value="0.0366487313200473" />
<inertia
ixx="9.28701176876329E-06"
ixy="-2.23878504272996E-11"
ixz="6.34310578103811E-07"
iyy="2.0727596617309E-05"
iyz="-1.71647322080315E-11"
izz="2.42416271089979E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link3.STL" />
</geometry>
<material
name="">
<color
rgba="0.1 0.1 0.1 0.9" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link3.STL" />
</geometry>
</collision>
</link>
<joint
name="joint3"
type="revolute">
<origin
xyz="0.033 -0.0001 0.179"
rpy="0 0 0" />
<parent
link="link2" />
<child
link="link3" />
<axis
xyz="0 -1 0" />
<limit
lower="-1.48"
upper="1.8"
effort="0"
velocity="0" />
</joint>
<link
name="link4">
<inertial>
<origin
xyz="0.0444029485674779 -0.00527865310158246 -1.43738021485262E-10"
rpy="0 0 0" />
<mass
value="0.124950088011432" />
<inertia
ixx="3.52699895078887E-05"
ixy="-1.14870103744551E-05"
ixz="2.45948329713632E-14"
iyy="0.00010928557067047"
iyz="-3.42525315676607E-12"
izz="0.000121451732690361" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link4.STL" />
</geometry>
<material
name="">
<color
rgba="0.1 0.1 0.1 0.9" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link4.STL" />
</geometry>
</collision>
</link>
<joint
name="joint4"
type="revolute">
<origin
xyz="0.0845 0 0"
rpy="0 0 0" />
<parent
link="link3" />
<child
link="link4" />
<axis
xyz="-1 0 0" />
<limit
lower="-2.90"
upper="2.90"
effort="0"
velocity="0" />
</joint>
<link
name="link5">
<inertial>
<origin
xyz="0.0391172635125616 1.22102848665318E-15 0.011359922796391"
rpy="0 0 0" />
<mass
value="0.0564710099602834" />
<inertia
ixx="1.77667699918498E-05"
ixy="3.77572698012408E-19"
ixz="-6.79618041712231E-07"
iyy="1.89643063051294E-05"
iyz="1.78381670331667E-19"
izz="1.66130972969903E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link5.STL" />
</geometry>
<material
name="">
<color
rgba="0.1 0.1 0.1 0.9" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link5.STL" />
</geometry>
</collision>
</link>
<joint
name="joint5"
type="revolute">
<origin
xyz="0.08435 0.00065 0"
rpy="0 0 0" />
<parent
link="link4" />
<child
link="link5" />
<axis
xyz="0 -1 0" />
<limit
lower="-1.8"
upper="1.60"
effort="0"
velocity="0" />
</joint>
<link
name="link6">
<inertial>
<origin
xyz="0.0330748503556987 -1.47583477394259E-10 0.00874151659437283"
rpy="0 0 0" />
<mass
value="0.0790875358325134" />
<inertia
ixx="4.00727396068743E-05"
ixy="1.5026227935429E-13"
ixz="6.77337873337555E-06"
iyy="4.37063090227749E-05"
iyz="-1.73263828329941E-13"
izz="5.69755186998711E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link6.STL" />
</geometry>
<material
name="">
<color
rgba="0.1 0.1 0.1 0.9" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link6.STL" />
</geometry>
</collision>
</link>
<joint
name="joint6"
type="revolute">
<origin
xyz="0.061387 0 0"
rpy="0 0 0" />
<parent
link="link5" />
<child
link="link6" />
<axis
xyz="-1 0 0" />
<limit
lower="-3.1"
upper="3.1"
effort="0"
velocity="0" />
</joint>
<link
name="usb_cam_link">
</link>
<joint
name="joint_usb_cam_frame"
type="fixed">
<origin
xyz="0.05 0 0.05825"
rpy="-1.57 0 -1.57" />
<parent
link="link6" />
<child
link="usb_cam_link" />
<axis
xyz="0 0 0" />
<limit
lower="0"
upper="0"
effort="0"
velocity="0" />
</joint>
<link
name="ar_tag_link">
</link>
<joint
name="joint_ar_tag_frame"
type="fixed">
<origin
xyz="0.025 0 0.036"
rpy="0 0 0" />
<parent
link="link6" />
<child
link="ar_tag_link" />
<axis
xyz="0 0 0" />
<limit
lower="0"
upper="0"
effort="0"
velocity="0" />
</joint>
<link
name="link_grasping_frame">
<inertial>
<origin
xyz="-0.29292863789122 -0.000855248417215765 -0.182862893125548"
rpy="0 0 0" />
<mass
value="1.55422651132493" />
<inertia
ixx="0.0246807389934657"
ixy="6.12977506319177E-05"
ixz="-0.0174568851774044"
iyy="0.0450160124726729"
iyz="0.000114187269419605"
izz="0.0218809326193524" />
</inertial>
</link>
<joint
name="joint_grasping_frame"
type="fixed">
<origin
xyz="0.0557 0 0"
rpy="0 0 0" />
<parent
link="link6" />
<child
link="link_grasping_frame" />
<axis
xyz="0 0 0" />
<limit
lower="0"
upper="0"
effort="0"
velocity="0" />
</joint>
<link
name="link_gripper_left">
<inertial>
<origin
xyz="0.0168448613850675 0.00562743947549268 -3.34157867051821E-05"
rpy="0 0 0" />
<mass
value="0.0185082696416839" />
<inertia
ixx="1.65620668352765E-06"
ixy="3.12039082733024E-07"
ixz="-1.06123823321138E-09"
iyy="7.56731403094351E-06"
iyz="5.54920898904154E-11"
izz="6.37610666327876E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link_gripper_left.STL" />
</geometry>
<material
name="">
<color
rgba="0.1 0.1 0.1 0.9" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link_gripper_left.STL" />
</geometry>
</collision>
</link>
<joint
name="joint_gripper_left"
type="prismatic">
<origin
xyz="0.0695 0.033 0"
rpy="0 0 0" />
<parent
link="link6" />
<child
link="link_gripper_left" />
<axis
xyz="0 1 0" />
<limit
lower="-0.034"
upper="0"
effort="0"
velocity="0" />
</joint>
<link
name="link_gripper_right">
<inertial>
<origin
xyz="0.0168448612901284 -0.00562743946967042 3.34158424380449E-05"
rpy="0 0 0" />
<mass
value="0.0185082695670405" />
<inertia
ixx="1.65620670013429E-06"
ixy="-3.12039085367371E-07"
ixz="1.06121397059487E-09"
iyy="7.56731399585561E-06"
iyz="5.54960746810554E-11"
izz="6.37610660879392E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link_gripper_right.STL" />
</geometry>
<material
name="">
<color
rgba="0.1 0.1 0.1 0.9" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://sagittarius_descriptions/meshes/link_gripper_right.STL" />
</geometry>
</collision>
</link>
<joint
name="joint_gripper_right"
type="prismatic">
<origin
xyz="0.0695 -0.033 0"
rpy="0 0 0" />
<parent
link="link6" />
<child
link="link_gripper_right" />
<axis
xyz="0 -1 0" />
<limit
lower="-0.034"
upper="0"
effort="0"
velocity="0" />
</joint>
</robot>

View File

@ -5,7 +5,7 @@
<arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/> <arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/>
<!--spark底盘驱动机器人描述,底盘,相机--> <!--spark底盘驱动机器人描述,底盘,相机-->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
</include> </include>
<!-- 启动雷达 --> <!-- 启动雷达 -->

View File

@ -16,7 +16,7 @@
<!-- spark底盘驱动机器人描述,底盘,相机 --> <!-- spark底盘驱动机器人描述,底盘,相机 -->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="start_base" value="true"/> <arg name="start_base" value="true"/>
</include> </include>
<!--UARM机械臂 --> <!--UARM机械臂 -->

View File

@ -10,7 +10,7 @@
<!--spark驱动机器人描述相机底盘--> <!--spark驱动机器人描述相机底盘-->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_type_tel)" /> <arg name="camera_type_tel" value="$(arg camera_type_tel)" />
</include> </include>
<!--摄像头订阅与视觉定位--> <!--摄像头订阅与视觉定位-->

View File

@ -5,7 +5,7 @@
<!--导航--> <!--导航-->
<include file="$(find spark_navigation)/launch/amcl_demo_lidar.launch"> <include file="$(find spark_navigation)/launch/amcl_demo_lidar.launch">
<arg name="camera_types" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="start_camera" value="true"> <arg name="start_camera" value="true">
</include> </include>

View File

@ -8,12 +8,12 @@
<!-- spark底盘驱动机器人描述,底盘,相机 --> <!-- spark底盘驱动机器人描述,底盘,相机 -->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
</include> </include>
<!-- --> <!-- -->
<include file="$(find spark_follower)/launch/nxfollower_bringup_nodelet.launch"> <include file="$(find spark_follower)/launch/nxfollower_bringup_nodelet.launch">
<arg name="camera_types" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
</include> </include>
<!--在rviz显示--> <!--在rviz显示-->

View File

@ -3,14 +3,14 @@
--> -->
<launch> <launch>
<arg name="camera_types" default="astrapro" /> <arg name="camera_type_tel" default="astrapro" />
<include file="$(find spark_follower)/launch/include/velocity_smoother.launch.xml"/> <include file="$(find spark_follower)/launch/include/velocity_smoother.launch.xml"/>
<node pkg="nodelet" type="nodelet" name="spark_base_nodelet_manager" args="manager"/> <node pkg="nodelet" type="nodelet" name="spark_base_nodelet_manager" args="manager"/>
<node pkg="nodelet" type="nodelet" name="nxfollower_nodelet" args="load nxfollower/NxFollowerNodelet spark_base_nodelet_manager" output="screen"> <node pkg="nodelet" type="nodelet" name="nxfollower_nodelet" args="load nxfollower/NxFollowerNodelet spark_base_nodelet_manager" output="screen">
<remap from="/camera/depth/points" to="/camera/depth_registered/points" if="$(eval arg('camera_types')=='d435')"/> <remap from="/camera/depth/points" to="/camera/depth_registered/points" if="$(eval arg('camera_type_tel')=='d435')"/>
</node> </node>
</launch> </launch>

View File

@ -1,11 +1,11 @@
<!--spark navigation lidar--> <!--spark navigation lidar-->
<launch> <launch>
<arg name="start_camera" default="false"/> <arg name="start_camera" default="false"/>
<arg name="camera_types" default="astrapro"/> <arg name="camera_type_tel" default="astrapro"/>
<arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/> <arg name="lidar_type_tel" default="3iroboticslidar2" doc="lidar type [3iroboticslidar2, ydlidar_g2]"/>
<!-- spark底盘驱动机器人描述,底盘,相机 --> <!-- spark底盘驱动机器人描述,底盘,相机 -->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_types)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="start_camera" value="$(arg start_camera)"/> <arg name="start_camera" value="$(arg start_camera)"/>
<arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
</include> </include>

View File

@ -5,7 +5,7 @@
<arg name="camera_type_tel" default="astrapro" doc="camera type [astrapro, astra, d435...]"/> <arg name="camera_type_tel" default="astrapro" doc="camera type [astrapro, astra, d435...]"/>
<!-- spark底盘驱动机器人描述,底盘,相机 --> <!-- spark底盘驱动机器人描述,底盘,相机 -->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
<arg name="start_camera" default="false"/> <arg name="start_camera" default="false"/>
</include> </include>

View File

@ -1,12 +1,12 @@
<!--rtab_demo --> <!--rtab_demo -->
<launch> <launch>
<!-- camera --> <!-- camera -->
<arg name="camera_types" default="" doc="camera type [astrapro, astra]"/> <arg name="camera_type_tel" default="" doc="camera type [astrapro, astra]"/>
<arg name="depthtolaser" default="/camera/depth/image_rect_raw"/> <arg name="depthtolaser" default="/camera/depth/image_rect_raw"/>
<!-- spark底盘驱动机器人描述,底盘,相机 --> <!-- spark底盘驱动机器人描述,底盘,相机 -->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_types)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="dp_rgist" value="true"/> <arg name="dp_rgist" value="true"/>
</include> </include>

View File

@ -1,16 +1,16 @@
<!--rtab_demo --> <!--rtab_demo -->
<launch> <launch>
<!-- camera --> <!-- camera -->
<arg name="camera_types" default="" doc="camera type [astrapro, astra]"/> <arg name="camera_type_tel" default="" doc="camera type [astrapro, astra]"/>
<arg name="depthtolaser" default="/camera/depth/points"/> <arg name="depthtolaser" default="/camera/depth/points"/>
<!-- spark底盘驱动机器人描述,底盘,相机 --> <!-- spark底盘驱动机器人描述,底盘,相机 -->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="camera_types" value="$(arg camera_types)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="dp_rgist" value="true"/> <arg name="dp_rgist" value="true"/>
</include> </include>
<!-- Run the depthimage_to_laserscan node --> <!-- Run the depthimage_to_laserscan node -->
<include file="$(find camera_driver_transfer)/launch/$(arg camera_types)_p2s.launch"> <include file="$(find camera_driver_transfer)/launch/$(arg camera_type_tel)_p2s.launch">
</include> </include>

View File

@ -10,7 +10,7 @@
<!-- spark底盘驱动机器人描述,底盘,相机 --> <!-- spark底盘驱动机器人描述,底盘,相机 -->
<include file="$(find spark_bringup)/launch/driver_bringup.launch"> <include file="$(find spark_bringup)/launch/driver_bringup.launch">
<arg name="start_camera" value="false"/> <arg name="start_camera" value="false"/>
<arg name="camera_types" value="$(arg camera_types)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
</include> </include>

View File

@ -7,7 +7,7 @@
<arg name="camera_type_tel" default="astrapro"/> <arg name="camera_type_tel" default="astrapro"/>
<include file="$(find spark_slam)/launch/2d_slam.launch"> <include file="$(find spark_slam)/launch/2d_slam.launch">
<arg name="slam_methods" value="$(arg slam_methods_tel)"/> <arg name="slam_methods" value="$(arg slam_methods_tel)"/>
<arg name="camera_types" value="$(arg camera_type_tel)"/> <arg name="camera_type_tel" value="$(arg camera_type_tel)"/>
<arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/> <arg name="lidar_type_tel" value="$(arg lidar_type_tel)"/>
</include> </include>
<!--创建新的终端spark键盘控制 “wsad”分别代表“前后左右”--> <!--创建新的终端spark键盘控制 “wsad”分别代表“前后左右”-->

View File

@ -93,16 +93,11 @@
<axis <axis
xyz="0 0 0" /> xyz="0 0 0" />
</joint> </joint>
<!-- lidar body, with origin at bottom screw mount -->
<joint name="lidar_joint" type="fixed">
<parent link="base_link"/>
<child link="lidar_bottom_screw_frame" />
</joint>
<link name="lidar_bottom_screw_frame"/>
<joint name="lidar_link_joint" type="fixed"> <joint name="lidar_link_joint" type="fixed">
<origin xyz="0 0 0.08" rpy="0 0 0"/> <origin xyz="0 0 0.08" rpy="0 0 0"/>
<parent link="lidar_bottom_screw_frame"/> <parent link="base_link"/>
<child link="lidar_link" /> <child link="lidar_link" />
</joint> </joint>
</robot> </robot>

View File

@ -32,6 +32,6 @@
<param name="range_max" type="double" value="25.0" /> <param name="range_max" type="double" value="25.0" />
<param name="frequency" type="double" value="10.0"/> <param name="frequency" type="double" value="10.0"/>
</node> </node>
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4" <!--node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
args="0.0 0.0 0.2 0.0 0.0 0.0 /base_footprint /laser_frame 40" /> args="0.0 0.0 0.2 0.0 0.0 0.0 /base_footprint /laser_frame 40" /-->
</launch> </launch>