#include <stdio.h>
#include <string.h>
#include <fcntl.h>
#include <sys/ioctl.h>
#include <net/if.h>
#include <linux/can.h>
#include <linux/can/raw.h>
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Quaternion.h>
#include <nav_msgs/Odometry.h>
#include <sensor_msgs/Joy.h>
#include <std_msgs/Float32.h>
#include <tf/transform_broadcaster.h>
#include <boost/thread/thread.hpp>
#include <boost/thread/mutex.hpp>
Go to the source code of this file.
Functions | |
int | can_open (const char *device) |
void | can_read_frames () |
int | can_send_cmd_vel (double speed, double yawspeed, int modestate=3) |
int | can_send_frame (struct can_frame *frame) |
void | can_task () |
void | cmdVelCallback (const geometry_msgs::Twist::ConstPtr &msg) |
int | main (int argc, char **argv) |
void | publishJoyMsg () |
void | publishOdomMsg () |
void | publishVoltageMsg () |
Variables | |
double | battery_voltage = 0 |
bool | can_running = false |
int | can_socket |
double | odom_orientation = 0 |
double | odom_pos_x = 0 |
double | odom_pos_y = 0 |
ros::Publisher | publisherJoy |
ros::Publisher | publisherOdom |
ros::Publisher | publisherVoltage |
uint8_t | remote_analog [8] |
uint8_t | remote_buttons [8] |
boost::mutex | ros_mutex |
int can_open | ( | const char * | device | ) |
Definition at line 45 of file innok_heros_can_driver.cpp.
void can_read_frames | ( | ) |
Definition at line 112 of file innok_heros_can_driver.cpp.
int can_send_cmd_vel | ( | double | speed, |
double | yawspeed, | ||
int | modestate = 3 |
||
) |
Definition at line 93 of file innok_heros_can_driver.cpp.
int can_send_frame | ( | struct can_frame * | frame | ) |
Definition at line 79 of file innok_heros_can_driver.cpp.
void can_task | ( | ) |
Definition at line 233 of file innok_heros_can_driver.cpp.
void cmdVelCallback | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |
Definition at line 227 of file innok_heros_can_driver.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 242 of file innok_heros_can_driver.cpp.
void publishJoyMsg | ( | ) |
Definition at line 201 of file innok_heros_can_driver.cpp.
void publishOdomMsg | ( | ) |
Definition at line 147 of file innok_heros_can_driver.cpp.
void publishVoltageMsg | ( | ) |
Definition at line 192 of file innok_heros_can_driver.cpp.
double battery_voltage = 0 |
Definition at line 30 of file innok_heros_can_driver.cpp.
bool can_running = false |
Definition at line 43 of file innok_heros_can_driver.cpp.
int can_socket |
Definition at line 28 of file innok_heros_can_driver.cpp.
double odom_orientation = 0 |
Definition at line 31 of file innok_heros_can_driver.cpp.
double odom_pos_x = 0 |
Definition at line 32 of file innok_heros_can_driver.cpp.
double odom_pos_y = 0 |
Definition at line 33 of file innok_heros_can_driver.cpp.
ros::Publisher publisherJoy |
Definition at line 39 of file innok_heros_can_driver.cpp.
ros::Publisher publisherOdom |
Definition at line 38 of file innok_heros_can_driver.cpp.
ros::Publisher publisherVoltage |
Definition at line 40 of file innok_heros_can_driver.cpp.
uint8_t remote_analog[8] |
Definition at line 36 of file innok_heros_can_driver.cpp.
uint8_t remote_buttons[8] |
Definition at line 35 of file innok_heros_can_driver.cpp.
boost::mutex ros_mutex |
Definition at line 42 of file innok_heros_can_driver.cpp.