Skip to content

Commit

Permalink
fix the conflict
Browse files Browse the repository at this point in the history
  • Loading branch information
dahang.li committed Aug 23, 2017
1 parent 6b5fc7f commit ccabb88
Show file tree
Hide file tree
Showing 4 changed files with 58 additions and 105 deletions.
20 changes: 1 addition & 19 deletions spark_v04/spark_app/spark_follower/src/nxfollower.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,16 +151,8 @@ class NxFollowerNode
}
}

<<<<<<< HEAD
/*
* @brief 发布底盘的速度,包括线速度和角速度
* @param [in] y 相对于机器人底盘base_footprint的目标点的y坐标
* @param [in] depth 相对于机器人底盘base_footprint的目标点的x坐标
*/
void pubCmd(float y, float depth)
=======

void pubCmd(const float &y, const float &depth)
>>>>>>> spark-04
{
double curr_dist = sqrt(y * y + depth * depth);
if (curr_dist == 0)
Expand All @@ -172,11 +164,7 @@ class NxFollowerNode
float x_linear = 0;
float z_angular = 0;
float z_scale = 1.2;
<<<<<<< HEAD
float x_scale = 6.0;
=======
float x_scale = 2.0;
>>>>>>> spark-04
x_linear = (depth - goal_depth_) * z_scale;
z_angular = asin(y / curr_dist) * x_scale;

Expand All @@ -191,13 +179,7 @@ class NxFollowerNode

cmdvel_pub.publish(cmd);
}
<<<<<<< HEAD
/*
* waiting for the end of the program
*/
=======

>>>>>>> spark-04
void spin()
{
ros::spin();
Expand Down
19 changes: 0 additions & 19 deletions spark_v04/spark_app/spark_follower/src/nxfollower_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,24 +36,5 @@ class NxFollowerNodelet : public nodelet::Nodelet
// watch the capitalization carefully
#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(nxfollower::NxFollowerNodelet, nodelet::Nodelet)
<<<<<<< HEAD
// PLUGINLIB_DECLARE_CLASS(usb_cam, usb_cam_nodelet, usb_cam::usb_cam_nodelet, nodelet::Nodelet);

#endif
/*
int main( int argc, char** argv )
{
ros::init(argc,argv,"orbcamera_node");
ros::NodeHandle nh;
NxCamera orb_cam(nh);
orb_cam.Init();
ros::AsyncSpinner spinner(6); // Use 4 threads
spinner.start();
ros::waitForShutdown();
return 0;
}
*/
=======

#endif
>>>>>>> spark-04
120 changes: 57 additions & 63 deletions spark_v04/spark_driver/b_3ilidar/include/b_3ilidar/rslidar_protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,17 +23,11 @@
//-----------------------------------------
#define COMM_HEAD_FLAGE 0xAA // Frame header

<<<<<<< HEAD
#define COMM_FRAME_TYPE_ATTR 0x20 // attribute frame
#define COMM_FRAME_TYPE_RSP_ATTR 0x21 // attribute frame

#define COMM_FRAME_TYPE_CMD 0x40 // command farme
=======
#define COMM_FRAME_TYPE_ATTR 0x20 // attribute frame
#define COMM_FRAME_TYPE_RSP_ATTR 0x21 // attribute frame

#define COMM_FRAME_TYPE_CMD 0x40 // command farme
>>>>>>> spark-04
#define COMM_FRAME_TYPE_RSP_CMD 0x41 // command farme

#define COMM_FRAME_TYPE_MESSAGE 0x61 // message frame
Expand Down Expand Up @@ -77,80 +71,80 @@
#define NOTE_BUFFER_PING 0x00
#define NOTE_BUFFER_PONG 0x01

/////////////命令帧命令字定义////////////////////////
/////////////����֡�����ֶ���////////////////////////
typedef enum _cmd_code
{
CMD_STOP = 0x01, //ֹͣ
CMD_START_SCAN, //开始扫描
CMD_INIT_DLIS2K, //初始化DLIS2K
CMD_WRITE_CAIL_DATA, //写标定数据 //三角激光雷达
CMD_WRITE_CAIL_DATA_TOF, //写标定数据 //TOF雷达
CMD_LASER_CTRL, //激光开关控制
CMD_DLIS2K_SAMPLE_DATA_8BIT, //设置输出CCD原始数据低8bit
CMD_DLIS2K_PIXEL_POS, //输出CCD的像素位置
CMD_LENS_FOCUS_MODE, //进入镜头调焦模式
CMD_PIXEL_POS_CAIL, //根据像素位置标定
CMD_MOTOR_WORK_CTRL, //马达控制
CMD_MOTOR_DUTY_SET, //设置马达驱动信号占空比
CMD_MOTOR_RPM_SET, //设置马达转速
CMD_DEBUG_MESSAGE_EN, //打印调试信息使能
CMD_EARE_CAIL_DATA, //擦除标定数据
CMD_REGAIN_DEFAUT_SET, //恢复出厂设置
CMD_DEVICE_ADDR_SET, //设定设备地址
CMD_SAMPLE_RATE_SET, //设定测量速率
CMD_DISTANCE_OFFSET, //设置测量距离偏移量
CMD_HIGH_VOLT_ADJUST, //微调高压
CMD_MEAS_PRINTF_EN, //设置测量信息打印使能
CMD_HIGH_VOLT_RATE, //设定高压系数
CMD_DISTANCE_RANGE, //设定测量单位
CMD_MEAS_UNIT, //设定测量单位
CMD_CAIL_MEAS, //设置不带、带标定测量
CMD_WIRELESS_POWER_CTRL, //无线供电开关控制
CMD_AUTO_MEAS, //开启、关闭上电自动测量
CMD_WRITE_FLASH, //写数据到FLASH
CMD_WRITE_DEVICE_INFO, //写产品相关信息
CMD_SYSTEM_RST, //系统复位
CMD_START_SCAN, //��ʼɨ��
CMD_INIT_DLIS2K, //��ʼ��DLIS2K
CMD_WRITE_CAIL_DATA, //д�궨���� //���Ǽ����״�
CMD_WRITE_CAIL_DATA_TOF, //д�궨���� //TOF�״�
CMD_LASER_CTRL, //���⿪�ؿ���
CMD_DLIS2K_SAMPLE_DATA_8BIT, //�������CCDԭʼ���ݵ�8bit
CMD_DLIS2K_PIXEL_POS, //���CCD�������
CMD_LENS_FOCUS_MODE, //���뾵ͷ����ģʽ
CMD_PIXEL_POS_CAIL, //��������λ�ñ궨
CMD_MOTOR_WORK_CTRL, //������
CMD_MOTOR_DUTY_SET, //������������ź�ռ�ձ�
CMD_MOTOR_RPM_SET, //�������ת��
CMD_DEBUG_MESSAGE_EN, //��ӡ������Ϣʹ��
CMD_EARE_CAIL_DATA, //�����궨����
CMD_REGAIN_DEFAUT_SET, //�ָ���������
CMD_DEVICE_ADDR_SET, //�趨�豸��ַ
CMD_SAMPLE_RATE_SET, //�趨��������
CMD_DISTANCE_OFFSET, //���ò�������ƫ����
CMD_HIGH_VOLT_ADJUST, //΢����ѹ
CMD_MEAS_PRINTF_EN, //���ò�����Ϣ��ӡʹ��
CMD_HIGH_VOLT_RATE, //�趨��ѹϵ��
CMD_DISTANCE_RANGE, //�趨������λ
CMD_MEAS_UNIT, //�趨������λ
CMD_CAIL_MEAS, //���ò��������궨����
CMD_WIRELESS_POWER_CTRL, //���߹��翪�ؿ���
CMD_AUTO_MEAS, //����ر��ϵ��Զ�����
CMD_WRITE_FLASH, //д���ݵ�FLASH
CMD_WRITE_DEVICE_INFO, //д��Ʒ�����Ϣ
CMD_SYSTEM_RST, //ϵͳ��λ
} CMD_CODE;

/////////////属性帧宏定义////////////////////////
/////////////����֡�궨��////////////////////////
typedef enum _attr_code
{

ATTR_READ_DEVICE_INFO = 0x53, //获取设备信息
ATTR_READ_DLIS2K_REG, //获取DLIS2K寄存器值
ATTR_READ_ONCE_MEAS, //获取单次测量值
ATTR_READ_CAIL_DATA, //获取标定数据
ATTR_READ_MOTOR_DUTY, //获取马达驱动信号占空比
ATTR_READ_MOTOR_RPM, //获取马达转速设定值
ATTR_READ_DEVICE_ADDR, //获取设备地址
ATTR_READ_SAMPLE_RATE, //获取测量速率
ATTR_READ_DISTANCE_OFFSET, //获取偏移量
ATTR_READ_HIGH_VOLT, //获取高压值
ATTR_READ_MEAS_KEYE_MESSAGE, //获取测量关键信息
ATTR_READ_HIGHT_VOLT_RATE, //获取高压系数
ATTR_READ_MEAS_RANGE, //获取测量量程
ATTR_READ_MEAS_UNIT, //获取测量单位
ATTR_READ_MEAS_MODE, //获取测量模式
ATTR_READ_FLASH_DATA, //读FLASH数据
ATTR_READ_DEVICE_HEALTH, //获取设备健康信息
ATTR_READ_DEVICE_INFO = 0x53, //��ȡ�豸��Ϣ
ATTR_READ_DLIS2K_REG, //��ȡDLIS2K�Ĵ���ֵ
ATTR_READ_ONCE_MEAS, //��ȡ���β���ֵ
ATTR_READ_CAIL_DATA, //��ȡ�궨����
ATTR_READ_MOTOR_DUTY, //��ȡ��������ź�ռ�ձ�
ATTR_READ_MOTOR_RPM, //��ȡ���ת���趨ֵ
ATTR_READ_DEVICE_ADDR, //��ȡ�豸��ַ
ATTR_READ_SAMPLE_RATE, //��ȡ��������
ATTR_READ_DISTANCE_OFFSET, //��ȡƫ����
ATTR_READ_HIGH_VOLT, //��ȡ��ѹֵ
ATTR_READ_MEAS_KEYE_MESSAGE, //��ȡ�����ؼ���Ϣ
ATTR_READ_HIGHT_VOLT_RATE, //��ȡ��ѹϵ��
ATTR_READ_MEAS_RANGE, //��ȡ��������
ATTR_READ_MEAS_UNIT, //��ȡ������λ
ATTR_READ_MEAS_MODE, //��ȡ����ģʽ
ATTR_READ_FLASH_DATA, //��FLASH����
ATTR_READ_DEVICE_HEALTH, //��ȡ�豸������Ϣ
} ATTR_CODE;

/////////////信息帧宏定义////////////////////////
/////////////��Ϣ֡�궨��////////////////////////
typedef enum _message_code
{

MESSAGE_DEVICE_ERROR = 0xA4, //报告设备故障
MESSAGE_DLIS2K_SAMPLE_DATA_8BIT, //报告CCD原始数据
MESSAGE_DLIS2K_PIXEL_POS, //报告CCD像素位置
MESSAGE_DLIS2K_PIXEL_POS_DIS, //报告CCD像素位置和距离
MESSAGE_TOF_DISTANCE, //报告TOF测距
MESSAGE_LIDAR_DISTANCE, //报告三角测距
MESSAGE_DEVICE_ERROR = 0xA4, //�����豸����
MESSAGE_DLIS2K_SAMPLE_DATA_8BIT, //����CCDԭʼ����
MESSAGE_DLIS2K_PIXEL_POS, //����CCD�����
MESSAGE_DLIS2K_PIXEL_POS_DIS, //����CCD����λ�ú;���
MESSAGE_TOF_DISTANCE, //����TOF���
MESSAGE_LIDAR_DISTANCE, //�������Dz��
} MESSAGE_CODE;

// Commonds
//-----------------------------------------

/////////////错误代码宏定义////////////////////////
/////////////�������궨��////////////////////////
typedef enum _comm_error_code
{
executeSuccess = 0,
Expand All @@ -161,7 +155,7 @@ typedef enum _comm_error_code
SIMPLE_CAIL_Error,
} COMM_ERROR_CODE;

/////////////通信帧结构////////////////////////////
/////////////ͨ��֡�ṹ////////////////////////////
typedef struct _comm_frame_t
{
uint8_t frameStart;
Expand Down
4 changes: 0 additions & 4 deletions spark_v04/spark_driver/b_3ilidar/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,11 +83,7 @@ class Threeiladar
Threeiladar(ros::NodeHandle in_nh)
{
nh = in_nh;
<<<<<<< HEAD
opt_com_path = "/dev/ttyUSB0";
=======
opt_com_path = "/dev/sparkBase";
>>>>>>> spark-04
if (!nh.getParam("/b_3ilidar_node/lidar_USB", opt_com_path))
ROS_ERROR("No lidar_USB param found, the serial port will be set as %s", opt_com_path.c_str());
opt_com_baudrate = 115200;
Expand Down

0 comments on commit ccabb88

Please sign in to comment.