Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Filter lateral acceleration #140

Merged
merged 5 commits into from
Nov 19, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -67,5 +67,7 @@ target_link_libraries(odom_gen libwaypoint_follower ${catkin_LIBRARIES})

add_executable(twist_filter nodes/twist_filter/twist_filter.cpp)
target_link_libraries(twist_filter ${catkin_LIBRARIES})
add_dependencies(twist_filter
runtime_manager_generate_messages_cpp)


Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<!-- -->
<launch>

<!-- rosrun waypoint_follower twist_filter -->
<node pkg="waypoint_follower" type="twist_filter" name="twist_filter" output="screen">
</node>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -32,38 +32,45 @@
#include <geometry_msgs/TwistStamped.h>

#include <iostream>
#include <chrono>

#define LOOP_RATE 100
#define FILTER_SIZE 3

#include "runtime_manager/ConfigTwistFilter.h"

//Publisher
static ros::Publisher g_twist_pub;
static double g_lateral_accel_limit = 0.8;

static void configCallback(const runtime_manager::ConfigTwistFilterConstPtr &config)
{
g_lateral_accel_limit = config->lateral_accel_limit;
ROS_INFO("g_lateral_accel_limit = %lf",g_lateral_accel_limit);
}

void TwistCmdCallback(const geometry_msgs::TwistStampedConstPtr &msg)
{
geometry_msgs::TwistStamped twist;
twist.twist.linear.x = msg->twist.linear.x;

static std::list<geometry_msgs::Twist> twist_list;
twist_list.push_back(msg->twist);
double accel = msg->twist.linear.x * msg->twist.angular.z;
ROS_INFO("lateral accel = %lf",accel);

if(twist_list.size() != FILTER_SIZE)
return;
else{
for(std::list<geometry_msgs::Twist>::const_iterator it = twist_list.begin(); it != twist_list.end();it++){
twist.twist.linear.x += it->linear.x;
twist.twist.angular.z += it->angular.z;
}
twist.twist.linear.x /= FILTER_SIZE;
twist.twist.angular.z /= FILTER_SIZE;

twist.header = msg->header;
g_twist_pub.publish(twist);

twist_list.pop_front();
if(fabs(accel) > g_lateral_accel_limit)
{
ROS_INFO("limit over! filtering...");
if(accel < 0)
twist.twist.angular.z = (-1) * g_lateral_accel_limit / msg->twist.linear.x;
else
twist.twist.angular.z = g_lateral_accel_limit / msg->twist.linear.x;
}
else
{
//ROS_INFO("limit clear!");
twist.twist.angular.z = msg->twist.angular.z;
}

ROS_INFO("twist.linear.x = %lf, twist.angular.z = %lf",twist.twist.linear.x,twist.twist.angular.z);
g_twist_pub.publish(twist);

}

Expand All @@ -74,12 +81,11 @@ int main(int argc, char **argv)

ros::NodeHandle nh;
ros::NodeHandle private_nh("~");

ros::Subscriber twist_sub = nh.subscribe("twist_raw", 1, TwistCmdCallback);
ros::Subscriber config_sub = nh.subscribe("config/twist_filter", 10, configCallback);
g_twist_pub = nh.advertise<geometry_msgs::TwistStamped>("twist_cmd", 1000);

ros::spin();



return 0;
}
1 change: 1 addition & 0 deletions ros/src/util/packages/runtime_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ add_message_files(
ConfigNdtMapping.msg
ConfigNdtMappingOutput.msg
ConfigWaypointFollower.msg
ConfigTwistFilter.msg
ConfigVelocitySet.msg
ConfigCarKf.msg
ConfigPedestrianKf.msg
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
Header header
float32 lateral_accel_limit
13 changes: 12 additions & 1 deletion ros/src/util/packages/runtime_manager/scripts/computing.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,8 @@ subs :
depend_bool : 'lambda v : v == 0'
stat_topic : [ lf ]
- name : twist_filter
cmd : rosrun waypoint_follower twist_filter
cmd : roslaunch waypoint_follower twist_filter.launch
param: twist_filter
- name : wf_simulator
cmd : roslaunch waypoint_follower wf_simulator.launch
param: wf_simulator
Expand Down Expand Up @@ -798,6 +799,16 @@ params :
dash : ''
delim : ':='

- name : twist_filter
topic : /config/twist_filter
msg : ConfigTwistFilter
vars :
- name : lateral_accel_limit
label : 'lateral_accel_limit :'
min : 0
max : 5.0
v : 0.8

- name : wf_simulator
vars :
- name : use_pose
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@
from runtime_manager.msg import ConfigNdtMapping
from runtime_manager.msg import ConfigNdtMappingOutput
from runtime_manager.msg import ConfigWaypointFollower
from runtime_manager.msg import ConfigTwistFilter
from runtime_manager.msg import ConfigVelocitySet
from runtime_manager.msg import ConfigCarKf
from runtime_manager.msg import ConfigPedestrianKf
Expand Down